2 #include <geometry_msgs/Pose.h> 3 #include <sensor_msgs/LaserScan.h> 8 #include <mrpt/version.h> 9 #include <mrpt/obs/CObservation2DRangeScan.h> 16 CObservation2DRangeScan& _obj)
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;
25 ASSERT_(_msg.ranges.size() > 1);
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;
33 for (std::size_t i_mrpt = 0; i_mrpt < N; i_mrpt++)
38 inv_ang_step * (-fov05 - _msg.angle_min + ang_step * i_mrpt);
41 else if (i_ros >= (
int)N)
45 const float r = _msg.ranges[i_ros];
46 _obj.setScanRange(i_mrpt, r);
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);
60 const size_t nRays = _obj.scan.size();
61 if (!nRays)
return false;
63 ASSERT_EQUAL_(_obj.scan.size(), _obj.validRange.size());
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);
70 _msg.time_increment = 0.0;
73 _msg.range_min = 0.02;
74 _msg.range_max = _obj.maxRange;
76 _msg.ranges.resize(nRays);
77 for (
size_t i = 0; i < nRays; i++) _msg.ranges[i] = _obj.scan[i];
81 _msg.header.frame_id = _obj.sensorLabel;
91 mrpt::poses::CPose3D pose;
92 _obj.getSensorPose(pose);
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)