#include <tools.h>
Public Types | |
| typedef pcl::PointXYZRGB | Point | 
| typedef pcl::PointCloud< Point > | PointCloud | 
Static Public Member Functions | |
| static tf::Transform | buildTransformation (cv::Mat rvec, cv::Mat tvec) | 
| compose the transformation matrix using 2 cv::Mat as inputs: one for rotation and one for translation   | |
| static string | convertTo5digits (int in) | 
| static void | getCameraModel (sensor_msgs::CameraInfo l_info_msg, sensor_msgs::CameraInfo r_info_msg, image_geometry::StereoCameraModel &stereo_camera_model, cv::Mat &camera_matrix) | 
| Get the stereo camera model from info messages.   | |
| static tf::Transform | getVertexPose (g2o::VertexSE3 *v) | 
| get the pose of vertex in format tf::Transform   | |
| static bool | imgMsgToMat (sensor_msgs::Image l_img_msg, sensor_msgs::Image r_img_msg, cv::Mat &l_img, cv::Mat &r_img) | 
| Convert image messages to cv cv::Mat.   | |
| static tf::Transform | isometryToTf (Eigen::Isometry3d in) | 
| convert a Eigen::Isometry3d to tf::transform   | |
| static tf::Transform | odomTotf (nav_msgs::Odometry odom_msg) | 
| Convert odometry message to tf::Transform.   | |
| static double | poseDiff2D (tf::Transform pose_1, tf::Transform pose_2) | 
| compute the absolute diference between 2 poses (omitting z)   | |
| static double | poseDiff3D (tf::Transform pose_1, tf::Transform pose_2) | 
| compute the absolute diference between 2 poses (omitting z)   | |
| static void | ratioMatching (cv::Mat desc_1, cv::Mat desc_2, double ratio, vector< cv::DMatch > &matches) | 
| Ration matching between descriptors.   | |
| static bool | sortByDistance (const pair< int, double > d1, const pair< int, double > d2) | 
| Sort 2 pairs by size.   | |
| static bool | sortByMatching (const pair< int, float > d1, const pair< int, float > d2) | 
| Sort 2 matchings by value.   | |
| static Eigen::Isometry3d | tfToIsometry (tf::Transform in) | 
| convert a tf::transform to Eigen::Isometry3d   | |
| static cv::Point3f | transformPoint (cv::Point3f point, tf::Transform base) | 
| static tf::Transform | transformVector4f (Eigen::Vector4f in, tf::Transform transform) | 
| Transform vector4f.   | |
| static tf::Transform | vector4fToTransform (Eigen::Vector4f in) | 
| convert a Eigen::Vector4f to tf::Transform   | |
| typedef pcl::PointXYZRGB tools::Tools::Point | 
| typedef pcl::PointCloud<Point> tools::Tools::PointCloud | 
| static tf::Transform tools::Tools::buildTransformation | ( | cv::Mat | rvec, | 
| cv::Mat | tvec | ||
| ) |  [inline, static] | 
        
| static string tools::Tools::convertTo5digits | ( | int | in | ) |  [inline, static] | 
        
| static void tools::Tools::getCameraModel | ( | sensor_msgs::CameraInfo | l_info_msg, | 
| sensor_msgs::CameraInfo | r_info_msg, | ||
| image_geometry::StereoCameraModel & | stereo_camera_model, | ||
| cv::Mat & | camera_matrix | ||
| ) |  [inline, static] | 
        
| static tf::Transform tools::Tools::getVertexPose | ( | g2o::VertexSE3 * | v | ) |  [inline, static] | 
        
| static bool tools::Tools::imgMsgToMat | ( | sensor_msgs::Image | l_img_msg, | 
| sensor_msgs::Image | r_img_msg, | ||
| cv::Mat & | l_img, | ||
| cv::Mat & | r_img | ||
| ) |  [inline, static] | 
        
| static tf::Transform tools::Tools::isometryToTf | ( | Eigen::Isometry3d | in | ) |  [inline, static] | 
        
| static tf::Transform tools::Tools::odomTotf | ( | nav_msgs::Odometry | odom_msg | ) |  [inline, static] | 
        
Convert odometry message to tf::Transform.
| rvec | cv matrix with the rotation angles | 
| tvec | cv matrix with the transformation x y z | 
| static double tools::Tools::poseDiff2D | ( | tf::Transform | pose_1, | 
| tf::Transform | pose_2 | ||
| ) |  [inline, static] | 
        
| static double tools::Tools::poseDiff3D | ( | tf::Transform | pose_1, | 
| tf::Transform | pose_2 | ||
| ) |  [inline, static] | 
        
| static void tools::Tools::ratioMatching | ( | cv::Mat | desc_1, | 
| cv::Mat | desc_2, | ||
| double | ratio, | ||
| vector< cv::DMatch > & | matches | ||
| ) |  [inline, static] | 
        
| static bool tools::Tools::sortByDistance | ( | const pair< int, double > | d1, | 
| const pair< int, double > | d2 | ||
| ) |  [inline, static] | 
        
| static bool tools::Tools::sortByMatching | ( | const pair< int, float > | d1, | 
| const pair< int, float > | d2 | ||
| ) |  [inline, static] | 
        
| static Eigen::Isometry3d tools::Tools::tfToIsometry | ( | tf::Transform | in | ) |  [inline, static] | 
        
| static cv::Point3f tools::Tools::transformPoint | ( | cv::Point3f | point, | 
| tf::Transform | base | ||
| ) |  [inline, static] | 
        
| static tf::Transform tools::Tools::transformVector4f | ( | Eigen::Vector4f | in, | 
| tf::Transform | transform | ||
| ) |  [inline, static] | 
        
| static tf::Transform tools::Tools::vector4fToTransform | ( | Eigen::Vector4f | in | ) |  [inline, static] | 
        
convert a Eigen::Vector4f to tf::Transform
| in | of type Eigen::Vector4f |