Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_LASER_SCAN_H
00002 #define MRPT_BRIDGE_LASER_SCAN_H
00003
00004 #include <stdint.h>
00005 #include <string>
00006
00007 namespace std
00008 {
00009 template <class T>
00010 class allocator;
00011 }
00012
00013 namespace geometry_msgs
00014 {
00015 template <class ContainerAllocator>
00016 struct Pose_;
00017 typedef Pose_<std::allocator<void>> Pose;
00018 }
00019
00020 namespace sensor_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct LaserScan_;
00024 typedef LaserScan_<std::allocator<void>> LaserScan;
00025 }
00026
00027 namespace mrpt
00028 {
00029 namespace poses
00030 {
00031 class CPose3D;
00032 }
00033 }
00034 #include <mrpt/version.h>
00035 namespace mrpt
00036 {
00037 namespace obs
00038 {
00039 class CObservation2DRangeScan;
00040 }
00041 }
00042
00043 namespace mrpt_bridge
00044 {
00053 bool convert(
00054 const sensor_msgs::LaserScan& _msg, const mrpt::poses::CPose3D& _pose,
00055 mrpt::obs::CObservation2DRangeScan& _obj);
00056
00062 bool convert(
00063 const mrpt::obs::CObservation2DRangeScan& _obj,
00064 sensor_msgs::LaserScan& _msg);
00065
00071 bool convert(
00072 const mrpt::obs::CObservation2DRangeScan& _obj,
00073 sensor_msgs::LaserScan& _msg, geometry_msgs::Pose& _pose);
00074
00077 }
00078
00079 #endif // MRPT_BRIDGE_LASER_SCAN_H