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 | |
| 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
| cam_info | |
| useRectifiedParameters | if 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. |
| tf::Transform ar_sys::getTf | ( | const cv::Mat & | Rvec, |
| const cv::Mat & | Tvec | ||
| ) |
getTf converts OpenCV coordinates to ROS Transform
| Rvec | |
| Tvec |
/* 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