Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_POINT_CLOUD2_H
00002 #define MRPT_BRIDGE_POINT_CLOUD2_H
00003
00004 namespace std
00005 {
00006 template <class T>
00007 class allocator;
00008 }
00009
00010 namespace std_msgs
00011 {
00012 template <class ContainerAllocator>
00013 struct Header_;
00014 typedef Header_<std::allocator<void>> Header;
00015 }
00016
00017 namespace sensor_msgs
00018 {
00019 template <class ContainerAllocator>
00020 struct PointCloud2_;
00021 typedef PointCloud2_<std::allocator<void>> PointCloud2;
00022 }
00023
00024 #include <mrpt/version.h>
00025 namespace mrpt
00026 {
00027 namespace maps
00028 {
00029 class CSimplePointsMap;
00030 class CColouredPointsMap;
00031 }
00032 }
00033
00034 namespace mrpt_bridge
00035 {
00045 bool copy(
00046 const sensor_msgs::PointCloud2& msg, mrpt::maps::CSimplePointsMap& obj);
00047
00057 bool copy(
00058 const mrpt::maps::CSimplePointsMap& obj, const std_msgs::Header& msg_header,
00059 sensor_msgs::PointCloud2& msg);
00060
00063 }
00064
00065 #endif // MRPT_BRIDGE_POINT_CLOUD2_H