Functions
mrpt_bridge::point_cloud Namespace Reference

Functions

bool mrpt2ros (const CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud &msg)
bool ros2mrpt (const sensor_msgs::PointCloud &msg, CSimplePointsMap &obj)

Detailed Description

Methods to convert between ROS msgs and MRPT objects for point-cloud datatypes.


Function Documentation

bool mrpt_bridge::point_cloud::mrpt2ros ( const CSimplePointsMap &  obj,
const std_msgs::Header &  msg_header,
sensor_msgs::PointCloud &  msg 
)

Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud::channels will be empty.

Returns:
true on sucessful conversion, false on any error.
See also:
ros2mrpt

Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud::channels will be empty.

Returns:
true on sucessful conversion, false on any error.

Definition at line 32 of file point_cloud.cpp.

bool mrpt_bridge::point_cloud::ros2mrpt ( const sensor_msgs::PointCloud &  msg,
CSimplePointsMap &  obj 
)

Convert sensor_msgs/PointCloud -> mrpt::maps::CSimplePointsMap CSimplePointsMap only contains (x,y,z) data, so sensor_msgs::PointCloud::channels are ignored.

Returns:
true on sucessful conversion, false on any error.
See also:
mrpt2ros

Convert sensor_msgs/PointCloud -> mrpt::slam::CSimplePointsMap

Returns:
true on sucessful conversion, false on any error.

Definition at line 11 of file point_cloud.cpp.



mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06