include/mrpt_bridge/beacon.h
Go to the documentation of this file.
1 #ifndef MRPT_BRIDGE_BEACON_H
2 #define MRPT_BRIDGE_BEACON_H
3 
4 #include <stdint.h>
5 #include <string>
6 
7 namespace std
8 {
9 template <class T>
10 class allocator;
11 }
12 
13 namespace geometry_msgs
14 {
15 template <class ContainerAllocator>
16 struct Pose_;
18 }
19 
20 namespace mrpt_msgs
21 {
22 template <class ContainerAllocator>
25 }
26 
27 namespace mrpt
28 {
29 namespace poses
30 {
31 class CPose3D;
32 }
33 }
34 #include <mrpt/version.h>
35 
36 namespace mrpt
37 {
38 namespace obs
39 {
40 class CObservationBeaconRanges;
41 }
42 }
43 
44 namespace mrpt_bridge
45 {
54 bool convert(
56  const mrpt::poses::CPose3D& _pose,
57 
58  mrpt::obs::CObservationBeaconRanges& _obj);
59 
65 bool convert(
66 
67  const mrpt::obs::CObservationBeaconRanges& _obj,
69 
76 bool convert(
77  const mrpt::obs::CObservationBeaconRanges& _obj,
79 
82 } // namespace mrpt_bridge
83 
84 #endif // MRPT_BRIDGE_BEACON_H
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
ObservationRangeBeacon_< std::allocator< void > > ObservationRangeBeacon
bool convert(const mrpt::obs::CObservationBeaconRanges &_obj, mrpt_msgs::ObservationRangeBeacon &_msg, geometry_msgs::Pose &_pose)


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