laser_scan.cpp
Go to the documentation of this file.
1 
2 #include <geometry_msgs/Pose.h>
3 #include <sensor_msgs/LaserScan.h>
4 #include "mrpt_bridge/time.h"
5 #include "mrpt_bridge/pose.h"
7 
8 #include <mrpt/version.h>
9 #include <mrpt/obs/CObservation2DRangeScan.h>
10 using namespace mrpt::obs;
11 
12 namespace mrpt_bridge
13 {
14 bool convert(
15  const sensor_msgs::LaserScan& _msg, const mrpt::poses::CPose3D& _pose,
16  CObservation2DRangeScan& _obj)
17 {
18  mrpt_bridge::convert(_msg.header.stamp, _obj.timestamp);
19  _obj.rightToLeft = true;
20  _obj.sensorLabel = _msg.header.frame_id;
21  _obj.aperture = _msg.angle_max - _msg.angle_min;
22  _obj.maxRange = _msg.range_max;
23  _obj.sensorPose = _pose;
24 
25  ASSERT_(_msg.ranges.size() > 1);
26 
27  const size_t N = _msg.ranges.size();
28  const double ang_step = _obj.aperture / (N - 1);
29  const double fov05 = 0.5 * _obj.aperture;
30  const double inv_ang_step = (N - 1) / _obj.aperture;
31 
32  _obj.resizeScan(N);
33  for (std::size_t i_mrpt = 0; i_mrpt < N; i_mrpt++)
34  {
35  // ROS indices go from _msg.angle_min to _msg.angle_max, while
36  // in MRPT they go from -FOV/2 to +FOV/2.
37  int i_ros =
38  inv_ang_step * (-fov05 - _msg.angle_min + ang_step * i_mrpt);
39  if (i_ros < 0)
40  i_ros += N;
41  else if (i_ros >= (int)N)
42  i_ros -= N; // wrap around 2PI...
43 
44  // set the scan
45  const float r = _msg.ranges[i_ros];
46  _obj.setScanRange(i_mrpt, r);
47 
48  // set the validity of the scan
49  const bool r_valid =
50  ((_obj.scan[i_mrpt] < (_msg.range_max * 0.95)) &&
51  (_obj.scan[i_mrpt] > _msg.range_min));
52  _obj.setScanRangeValidity(i_mrpt, r_valid);
53  }
54 
55  return true;
56 }
57 
58 bool convert(const CObservation2DRangeScan& _obj, sensor_msgs::LaserScan& _msg)
59 {
60  const size_t nRays = _obj.scan.size();
61  if (!nRays) return false;
62 
63  ASSERT_EQUAL_(_obj.scan.size(), _obj.validRange.size());
64 
65  _msg.angle_min = -0.5f * _obj.aperture;
66  _msg.angle_max = 0.5f * _obj.aperture;
67  _msg.angle_increment = _obj.aperture / (_obj.scan.size() - 1);
68 
69  // setting the following values to zero solves a rviz visualization problem
70  _msg.time_increment = 0.0; // 1./30.; // Anything better?
71  _msg.scan_time = 0.0; // _msg.time_increment; // idem?
72 
73  _msg.range_min = 0.02;
74  _msg.range_max = _obj.maxRange;
75 
76  _msg.ranges.resize(nRays);
77  for (size_t i = 0; i < nRays; i++) _msg.ranges[i] = _obj.scan[i];
78 
79  // Set header data:
80  mrpt_bridge::convert(_obj.timestamp, _msg.header.stamp);
81  _msg.header.frame_id = _obj.sensorLabel;
82 
83  return true;
84 }
85 
86 bool convert(
87  const CObservation2DRangeScan& _obj, sensor_msgs::LaserScan& _msg,
88  geometry_msgs::Pose& _pose)
89 {
90  convert(_obj, _msg);
91  mrpt::poses::CPose3D pose;
92  _obj.getSensorPose(pose);
93  convert(pose, _pose);
94  return true;
95 }
96 } // end namespace
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
bool convert(const CObservation2DRangeScan &_obj, sensor_msgs::LaserScan &_msg, geometry_msgs::Pose &_pose)
Definition: laser_scan.cpp:86


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