Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_POINT_CLOUD_H
00002 #define MRPT_BRIDGE_POINT_CLOUD_H
00003
00004 #include <sensor_msgs/PointCloud.h>
00005 #include <mrpt/slam/CSimplePointsMap.h>
00006 #include <mrpt/slam/CColouredPointsMap.h>
00007
00008 namespace mrpt_bridge {
00009
00012 namespace point_cloud
00013 {
00019 bool ros2mrpt(
00020 const sensor_msgs::PointCloud &msg,
00021 mrpt::slam::CSimplePointsMap &obj
00022 );
00023
00031 bool mrpt2ros(
00032 const mrpt::slam::CSimplePointsMap &obj,
00033 const std_msgs::Header &msg_header,
00034 sensor_msgs::PointCloud &msg
00035 );
00036 };
00037 }
00038
00039 #endif //MRPT_BRIDGE_POINT_CLOUD_H