Public Types | Static Public Member Functions
tools::Tools Class Reference

#include <tools.h>

List of all members.

Public Types

typedef pcl::PointXYZRGB Point
typedef pcl::PointCloud< PointPointCloud

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

Detailed Description

Definition at line 24 of file tools.h.


Member Typedef Documentation

typedef pcl::PointXYZRGB tools::Tools::Point

Definition at line 30 of file tools.h.

Definition at line 31 of file tools.h.


Member Function Documentation

static tf::Transform tools::Tools::buildTransformation ( cv::Mat  rvec,
cv::Mat  tvec 
) [inline, static]

compose the transformation matrix using 2 cv::Mat as inputs: one for rotation and one for translation

Returns:
the transformation matrix
Parameters:
rveccv matrix with the rotation angles
tveccv matrix with the transformation x y z

Definition at line 245 of file tools.h.

static string tools::Tools::convertTo5digits ( int  in) [inline, static]

Definition at line 295 of file tools.h.

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]

Get the stereo camera model from info messages.

Parameters:
leftimage info message.
rightimage info message.
willcontain the output camera model.
willcontain the output camera matrix.

Definition at line 160 of file tools.h.

static tf::Transform tools::Tools::getVertexPose ( g2o::VertexSE3 *  v) [inline, static]

get the pose of vertex in format tf::Transform

Returns:
tf::Transform pose matrix
Parameters:
vertex

Definition at line 190 of file tools.h.

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]

Convert image messages to cv cv::Mat.

Parameters:
leftimage message.
rightimage message.
willcontain the output left cv::Mat.
willcontain the output right cv::Mat.

Definition at line 131 of file tools.h.

static tf::Transform tools::Tools::isometryToTf ( Eigen::Isometry3d  in) [inline, static]

convert a Eigen::Isometry3d to tf::transform

Returns:
tf::transform matrix
Parameters:
inof type Eigen::Isometry3d

Definition at line 82 of file tools.h.

static tf::Transform tools::Tools::odomTotf ( nav_msgs::Odometry  odom_msg) [inline, static]

Convert odometry message to tf::Transform.

Returns:
the trasnformation matrix
Parameters:
rveccv matrix with the rotation angles
tveccv matrix with the transformation x y z

Definition at line 97 of file tools.h.

static double tools::Tools::poseDiff2D ( tf::Transform  pose_1,
tf::Transform  pose_2 
) [inline, static]

compute the absolute diference between 2 poses (omitting z)

Returns:
the norm between two poses
Parameters:
pose_1transformation matrix of pose 1
pose_2transformation matrix of pose 2

Definition at line 213 of file tools.h.

static double tools::Tools::poseDiff3D ( tf::Transform  pose_1,
tf::Transform  pose_2 
) [inline, static]

compute the absolute diference between 2 poses (omitting z)

Returns:
the norm between two poses
Parameters:
pose_1transformation matrix of pose 1
pose_2transformation matrix of pose 2

Definition at line 202 of file tools.h.

static void tools::Tools::ratioMatching ( cv::Mat  desc_1,
cv::Mat  desc_2,
double  ratio,
vector< cv::DMatch > &  matches 
) [inline, static]

Ration matching between descriptors.

Parameters:
Descriptorsof image 1
Descriptorsof image 2
ratiovalue (0.6/0.9)
outputmatching

Definition at line 276 of file tools.h.

static bool tools::Tools::sortByDistance ( const pair< int, double >  d1,
const pair< int, double >  d2 
) [inline, static]

Sort 2 pairs by size.

Returns:
true if pair 1 is smaller than pair 2
Parameters:
pair1
pair2

Definition at line 234 of file tools.h.

static bool tools::Tools::sortByMatching ( const pair< int, float >  d1,
const pair< int, float >  d2 
) [inline, static]

Sort 2 matchings by value.

Returns:
true if matching 1 is smaller than matching 2
Parameters:
matching1
matching2

Definition at line 224 of file tools.h.

static Eigen::Isometry3d tools::Tools::tfToIsometry ( tf::Transform  in) [inline, static]

convert a tf::transform to Eigen::Isometry3d

Returns:
Eigen::Isometry3d matrix
Parameters:
inof type tf::transform

Definition at line 62 of file tools.h.

static cv::Point3f tools::Tools::transformPoint ( cv::Point3f  point,
tf::Transform  base 
) [inline, static]

Definition at line 262 of file tools.h.

static tf::Transform tools::Tools::transformVector4f ( Eigen::Vector4f  in,
tf::Transform  transform 
) [inline, static]

Transform vector4f.

Returns:
transformed Eigen::Vector4f
Parameters:
inputEigen::Vector4f
inputtransformation

Definition at line 52 of file tools.h.

static tf::Transform tools::Tools::vector4fToTransform ( Eigen::Vector4f  in) [inline, static]

convert a Eigen::Vector4f to tf::Transform

Returns:
tf::Transform matrix
Parameters:
inof type Eigen::Vector4f

Definition at line 38 of file tools.h.


The documentation for this class was generated from the following file:


stereo_slam
Author(s): Pep Lluis Negre
autogenerated on Thu Jul 14 2016 04:09:13