10 #include <geometry_msgs/Pose.h>
11 #include <sensor_msgs/LaserScan.h>
16 #include <mrpt/version.h>
17 #include <mrpt/obs/CObservation2DRangeScan.h>
24 CObservation2DRangeScan& _obj)
27 _obj.rightToLeft =
true;
28 _obj.sensorLabel = _msg.header.frame_id;
29 _obj.aperture = _msg.angle_max - _msg.angle_min;
30 _obj.maxRange = _msg.range_max;
31 _obj.sensorPose = _pose;
33 ASSERT_(_msg.ranges.size() > 1);
35 const size_t N = _msg.ranges.size();
36 const double ang_step = _obj.aperture / (N - 1);
37 const double fov05 = 0.5 * _obj.aperture;
38 const double inv_ang_step = (N - 1) / _obj.aperture;
41 for (std::size_t i_mrpt = 0; i_mrpt < N; i_mrpt++)
46 inv_ang_step * (-fov05 - _msg.angle_min + ang_step * i_mrpt);
49 else if (i_ros >= (
int)N)
53 const float r = _msg.ranges[i_ros];
54 _obj.setScanRange(i_mrpt, r);
58 ((_obj.getScanRange(i_mrpt) < (_msg.range_max * 0.95)) &&
59 (_obj.getScanRange(i_mrpt) > _msg.range_min));
60 _obj.setScanRangeValidity(i_mrpt, r_valid);
68 const size_t nRays = _obj.getScanSize();
69 if (!nRays)
return false;
71 _msg.angle_min = -0.5f * _obj.aperture;
72 _msg.angle_max = 0.5f * _obj.aperture;
73 _msg.angle_increment = _obj.aperture / (_obj.getScanSize() - 1);
76 _msg.time_increment = 0.0;
79 _msg.range_min = 0.02;
80 _msg.range_max = _obj.maxRange;
82 _msg.ranges.resize(nRays);
83 for (
size_t i = 0; i < nRays; i++) _msg.ranges[i] = _obj.getScanRange(i);
87 _msg.header.frame_id = _obj.sensorLabel;
97 mrpt::poses::CPose3D pose;
98 _obj.getSensorPose(pose);