beacon.h
Go to the documentation of this file.
00001 #ifndef MRPT_BRIDGE_BEACON_H
00002 #define MRPT_BRIDGE_BEACON_H
00003 
00004 
00005 
00006 #include <stdint.h>
00007 #include <string>
00008 
00009 namespace std{
00010     template <class T> class allocator;
00011 }
00012 
00013 namespace geometry_msgs{
00014     template <class ContainerAllocator> struct Pose_;
00015     typedef Pose_<std::allocator<void> > Pose;
00016 }
00017 
00018 namespace mrpt_msgs{
00019     template <class ContainerAllocator> struct ObservationRangeBeacon_;
00020     typedef ObservationRangeBeacon_<std::allocator<void> > ObservationRangeBeacon;
00021 }
00022 
00023 namespace mrpt { namespace poses { class CPose3D; } }
00024 #include <mrpt/version.h>
00025 #if MRPT_VERSION>=0x130
00026         namespace mrpt { namespace obs { class CObservationBeaconRanges; } }
00027 #else
00028         namespace mrpt { namespace slam  { class CObservationBeaconRanges; } }
00029 #endif
00030 
00031 namespace mrpt_bridge {
00032 
00040         bool convert(
00041                         const mrpt_msgs::ObservationRangeBeacon &_msg,
00042                         const mrpt::poses::CPose3D &_pose,
00043 #if MRPT_VERSION>=0x130
00044                         mrpt::obs::CObservationBeaconRanges &_obj
00045 #else
00046                         mrpt::slam::CObservationBeaconRanges &_obj
00047 #endif
00048                         );
00049 
00054         bool convert(
00055 #if MRPT_VERSION>=0x130
00056                 const mrpt::obs::CObservationBeaconRanges &_obj,
00057 #else
00058                 const mrpt::slam::CObservationBeaconRanges &_obj,
00059 #endif
00060                 mrpt_msgs::ObservationRangeBeacon &_msg);
00061 
00066         bool convert(
00067                 #if MRPT_VERSION>=0x130
00068                                 const mrpt::obs::CObservationBeaconRanges &_obj,
00069                 #else
00070                                 const mrpt::slam::CObservationBeaconRanges &_obj,
00071                 #endif
00072                 mrpt_msgs::ObservationRangeBeacon &_msg,
00073                 geometry_msgs::Pose &_pose);
00074 
00077 } //namespace mrpt_bridge
00078 
00079 #endif //MRPT_BRIDGE_BEACON_H


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06