laser_scan.h
Go to the documentation of this file.
1 #ifndef MRPT_BRIDGE_LASER_SCAN_H
2 #define MRPT_BRIDGE_LASER_SCAN_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_;
17 typedef Pose_<std::allocator<void>> Pose;
18 }
19 
20 namespace sensor_msgs
21 {
22 template <class ContainerAllocator>
23 struct LaserScan_;
25 }
26 
27 namespace mrpt
28 {
29 namespace poses
30 {
31 class CPose3D;
32 }
33 }
34 #include <mrpt/version.h>
35 namespace mrpt
36 {
37 namespace obs
38 {
39 class CObservation2DRangeScan;
40 }
41 }
42 
43 namespace mrpt_bridge
44 {
53 bool convert(
54  const sensor_msgs::LaserScan& _msg, const mrpt::poses::CPose3D& _pose,
55  mrpt::obs::CObservation2DRangeScan& _obj);
56 
62 bool convert(
63  const mrpt::obs::CObservation2DRangeScan& _obj,
65 
71 bool convert(
72  const mrpt::obs::CObservation2DRangeScan& _obj,
74 
77 } // namespace mrpt_bridge
78 
79 #endif // MRPT_BRIDGE_LASER_SCAN_H
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool convert(const mrpt::obs::CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg, geometry_msgs::Pose &_pose)
LaserScan_< std::allocator< void > > LaserScan
Definition: laser_scan.h:23


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