Functions
ar_sys Namespace Reference

Functions

aruco::CameraParameters getCamParams (const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
 getCamParams gets the camera intrinsics from a CameraInfo message and copies them to ar_sys own data structure
tf::Transform getTf (const cv::Mat &Rvec, const cv::Mat &Tvec)
 getTf converts OpenCV coordinates to ROS Transform

Function Documentation

aruco::CameraParameters ar_sys::getCamParams ( const sensor_msgs::CameraInfo &  cam_info,
bool  useRectifiedParameters 
)

getCamParams gets the camera intrinsics from a CameraInfo message and copies them to ar_sys own data structure

Parameters:
cam_info
useRectifiedParametersif true, the intrinsics are taken from cam_info.P and the distortion parameters are set to 0. Otherwise, cam_info.K and cam_info.D are taken.
Returns:

Definition at line 15 of file utils.cpp.

tf::Transform ar_sys::getTf ( const cv::Mat &  Rvec,
const cv::Mat &  Tvec 
)

getTf converts OpenCV coordinates to ROS Transform

Parameters:
Rvec
Tvec
Returns:
tf::Transform

/* Fixed the rotation to meet the ROS system /* Doing a basic rotation around X with theta=PI /* By Sahloul /* See http://en.wikipedia.org/wiki/Rotation_matrix for details

Definition at line 44 of file utils.cpp.



ar_sys
Author(s): Hamdi Sahloul , Rafael Muñoz Salinas , Bence Magyar
autogenerated on Thu Aug 27 2015 12:23:55