src/beacon.h
Go to the documentation of this file.
1 #ifndef MRPT_BRIDGE_BEACON_H
2 #define MRPT_BRIDGE_BEACON_H
3 
4 
5 
6 #include <stdint.h>
7 #include <string>
8 
9 namespace std{
10  template <class T> class allocator;
11 }
12 
13 namespace geometry_msgs{
14  template <class ContainerAllocator> struct Pose_;
15  typedef Pose_<std::allocator<void> > Pose;
16 }
17 
18 namespace mrpt_msgs{
19  template <class ContainerAllocator> struct ObservationRangeBeacon_;
20  typedef ObservationRangeBeacon_<std::allocator<void> > ObservationRangeBeacon;
21 }
22 
23 namespace mrpt { namespace poses { class CPose3D; } }
24 #include <mrpt/version.h>
25 #if MRPT_VERSION>=0x130
26  namespace mrpt { namespace obs { class CObservationBeaconRanges; } }
27 #else
28  namespace mrpt { namespace slam { class CObservationBeaconRanges; } }
29 #endif
30 
31 namespace mrpt_bridge {
32 
40  bool convert(
42  const mrpt::poses::CPose3D &_pose,
43 #if MRPT_VERSION>=0x130
44  mrpt::obs::CObservationBeaconRanges &_obj
45 #else
46  mrpt::slam::CObservationBeaconRanges &_obj
47 #endif
48  );
49 
54  bool convert(
55 #if MRPT_VERSION>=0x130
56  const mrpt::obs::CObservationBeaconRanges &_obj,
57 #else
58  const mrpt::slam::CObservationBeaconRanges &_obj,
59 #endif
61 
66  bool convert(
67  #if MRPT_VERSION>=0x130
68  const mrpt::obs::CObservationBeaconRanges &_obj,
69  #else
70  const mrpt::slam::CObservationBeaconRanges &_obj,
71  #endif
73  geometry_msgs::Pose &_pose);
74 
77 } //namespace mrpt_bridge
78 
79 #endif //MRPT_BRIDGE_BEACON_H
bool convert(const mrpt::slam::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg, geometry_msgs::Pose &_pose)
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
ObservationRangeBeacon_< std::allocator< void > > ObservationRangeBeacon


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Sat Apr 28 2018 02:49:17