#include <tools.h>
Classes | |
struct | FilterParams |
Public Types | |
typedef pcl::PointXYZRGB | Point |
typedef pcl::PointCloud< Point > | PointCloud |
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 |
typedef pcl::PointXYZRGB tools::Tools::Point |
typedef pcl::PointCloud<Point> tools::Tools::PointCloud |
static void tools::Tools::filterPointCloud | ( | PointCloud::Ptr | cloud, |
tools::Tools::FilterParams | params | ||
) | [inline, static] |
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] |
static tf::Transform tools::Tools::getVertexPose | ( | slam::Vertex * | v | ) | [inline, static] |
get the pose of vertex in format tf::Transform
vertex | of type Vertex |
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] |
static string tools::Tools::isometryToString | ( | Eigen::Isometry3d | m | ) | [inline, static] |
static tf::Transform tools::Tools::isometryToTf | ( | Eigen::Isometry3d | in | ) | [inline, static] |
static tf::Transform tools::Tools::matrix4fToTf | ( | Eigen::Matrix4f | 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::poseDiff | ( | tf::Transform | pose_1, |
tf::Transform | pose_2 | ||
) | [inline, static] |
static void tools::Tools::showTf | ( | tf::Transform | input | ) | [inline, static] |
static bool tools::Tools::sortByDistance | ( | const pair< int, double > | d1, |
const pair< int, double > | d2 | ||
) | [inline, static] |
static Eigen::Isometry3d tools::Tools::tfToIsometry | ( | tf::Transform | in | ) | [inline, static] |
static Eigen::Matrix4f tools::Tools::tfToMatrix4f | ( | tf::Transform | in | ) | [inline, static] |