marker_msgs.h
Go to the documentation of this file.
1 
9 #ifndef MRPT_BRIDGE_MARKER_MSGS_H
10 #define MRPT_BRIDGE_MARKER_MSGS_H
11 
12 #include <marker_msgs/MarkerDetection.h>
13 #include <mrpt/obs/CObservationRange.h>
14 #include <mrpt/obs/CObservation2DRangeScan.h>
15 #include <mrpt/obs/CObservationBearingRange.h>
16 #include <mrpt/obs/CObservationBeaconRanges.h>
17 
18 
19 namespace std
20 {
21 template <class T>
22 class allocator;
23 }
24 
25 namespace geometry_msgs
26 {
27 template <class ContainerAllocator>
28 struct Pose_;
29 typedef Pose_<std::allocator<void>> Pose;
30 }
31 
32 namespace marker_msgs
33 {
34 template <class ContainerAllocator>
37 }
38 
39 namespace mrpt
40 {
41 namespace poses
42 {
43 class CPose3D;
44 }
45 }
46 
47 #include <mrpt/version.h>
48 namespace mrpt
49 {
50 namespace obs
51 {
52 class CObservationBearingRange;
53 }
54 }
55 
56 namespace mrpt_bridge
57 {
58 
59  bool convert(const marker_msgs::MarkerDetection& _msg, const mrpt::poses::CPose3D& _pose, mrpt::obs::CObservationBearingRange& _obj);
60  bool convert(const marker_msgs::MarkerDetection& _msg, const mrpt::poses::CPose3D& _pose, mrpt::obs::CObservationBeaconRanges& _obj);
61 }
62 
63 #endif //MRPT_BRIDGE_MARKER_MSGS_H
MarkerDetection_< std::allocator< void > > MarkerDetection
Definition: marker_msgs.h:35
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool convert(const marker_msgs::MarkerDetection &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
Definition: marker_msgs.cpp:44


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