Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_POINT_CLOUD2_H
00002 #define MRPT_BRIDGE_POINT_CLOUD2_H
00003
00004
00005 namespace std{
00006 template <class T> class allocator;
00007 }
00008
00009 namespace std_msgs{
00010 template <class ContainerAllocator> struct Header_;
00011 typedef Header_<std::allocator<void> > Header;
00012 }
00013
00014 namespace sensor_msgs{
00015 template <class ContainerAllocator> struct PointCloud2_;
00016 typedef PointCloud2_<std::allocator<void> > PointCloud2;
00017 }
00018
00019 namespace mrpt
00020 {
00021 namespace slam
00022 {
00023 class CSimplePointsMap;
00024 class CColouredPointsMap;
00025 }
00026 }
00027 namespace mrpt_bridge
00028 {
00029
00035 bool copy(const sensor_msgs::PointCloud2 &msg, mrpt::slam::CSimplePointsMap &obj);
00036
00044 bool copy(const mrpt::slam::CSimplePointsMap &obj, const std_msgs::Header &msg_header,
00045 sensor_msgs::PointCloud2 &msg);
00046
00047 }
00048
00049 #endif //MRPT_BRIDGE_POINT_CLOUD2_H