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) |
Methods to convert between ROS msgs and MRPT objects for point-cloud datatypes.
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.
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.
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.
Convert sensor_msgs/PointCloud -> mrpt::slam::CSimplePointsMap
Definition at line 11 of file point_cloud.cpp.