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

#include <tools.h>

List of all members.

Classes

struct  FilterParams

Public Types

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

Static Public Member Functions

static void filterPointCloud (PointCloud::Ptr cloud, tools::Tools::FilterParams params)
 Filter some pointcloud.
static bool getCameraModel (sensor_msgs::CameraInfo l_info_msg, sensor_msgs::CameraInfo r_info_msg, image_geometry::StereoCameraModel &stereo_camera_model, Mat &camera_matrix)
 Get the stereo camera model from info messages.
static tf::Transform getVertexPose (slam::Vertex *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, Mat &l_img, Mat &r_img)
 Convert image messages to cv Mat.
static string isometryToString (Eigen::Isometry3d m)
 Convert isometry to string (useful for debugin purposes)
static tf::Transform isometryToTf (Eigen::Isometry3d in)
 convert a Eigen::Isometry3d to tf::transform
static tf::Transform matrix4fToTf (Eigen::Matrix4f in)
 convert a Eigen::Matrix4f to tf::transform
static tf::Transform odomTotf (nav_msgs::Odometry odom_msg)
 Convert odometry message to tf::Transform.
static double poseDiff (tf::Transform pose_1, tf::Transform pose_2)
 compute the absolute diference between 2 poses
static void showTf (tf::Transform input)
 Show a tf in the console (useful for debugin purposes)
static bool sortByDistance (const pair< int, double > d1, const pair< int, double > d2)
 Sort 2 pairs by size.
static Eigen::Isometry3d tfToIsometry (tf::Transform in)
 convert a tf::transform to Eigen::Isometry3d
static Eigen::Matrix4f tfToMatrix4f (tf::Transform in)
 convert a tf::transform to Eigen::Matrix4f

Detailed Description

Definition at line 23 of file tools.h.


Member Typedef Documentation

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

Definition at line 28 of file tools.h.

Definition at line 29 of file tools.h.


Member Function Documentation

static void tools::Tools::filterPointCloud ( PointCloud::Ptr  cloud,
tools::Tools::FilterParams  params 
) [inline, static]

Filter some pointcloud.

Returns:
Parameters:
theinput pointcloud (will be overwritten)

Definition at line 289 of file tools.h.

static bool tools::Tools::getCameraModel ( sensor_msgs::CameraInfo  l_info_msg,
sensor_msgs::CameraInfo  r_info_msg,
image_geometry::StereoCameraModel stereo_camera_model,
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 197 of file tools.h.

static tf::Transform tools::Tools::getVertexPose ( slam::Vertex v) [inline, static]

get the pose of vertex in format tf::Transform

Returns:
tf::Transform pose matrix
Parameters:
vertexof type Vertex

Definition at line 225 of file tools.h.

static bool tools::Tools::imgMsgToMat ( sensor_msgs::Image  l_img_msg,
sensor_msgs::Image  r_img_msg,
Mat &  l_img,
Mat &  r_img 
) [inline, static]

Convert image messages to cv Mat.

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

Definition at line 173 of file tools.h.

static string tools::Tools::isometryToString ( Eigen::Isometry3d  m) [inline, static]

Convert isometry to string (useful for debugin purposes)

Returns:
string containing the isometry
Parameters:
isometrymatrix

Definition at line 257 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 104 of file tools.h.

static tf::Transform tools::Tools::matrix4fToTf ( Eigen::Matrix4f  in) [inline, static]

convert a Eigen::Matrix4f to tf::transform

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

Definition at line 118 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 139 of file tools.h.

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

compute the absolute diference between 2 poses

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

Definition at line 237 of file tools.h.

static void tools::Tools::showTf ( tf::Transform  input) [inline, static]

Show a tf in the console (useful for debugin purposes)

Returns:
Parameters:
tfmatrix

Definition at line 273 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 248 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 Eigen::Matrix4f tools::Tools::tfToMatrix4f ( tf::Transform  in) [inline, static]

convert a tf::transform to Eigen::Matrix4f

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

Definition at line 82 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 Aug 27 2015 15:24:22