10 #include <geometry_msgs/Pose.h> 11 #include <sensor_msgs/LaserScan.h> 16 #include <mrpt/version.h> 17 #include <mrpt/obs/CObservation2DRangeScan.h> 29 _obj.
aperture = _msg.angle_max - _msg.angle_min;
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];
58 ((_obj.
getScanRange(i_mrpt) < (_msg.range_max * 0.95)) &&
69 if (!nRays)
return false;
71 _msg.angle_min = -0.5f * _obj.
aperture;
72 _msg.angle_max = 0.5f * _obj.
aperture;
76 _msg.time_increment = 0.0;
79 _msg.range_min = 0.02;
82 _msg.ranges.resize(nRays);
83 for (
size_t i = 0; i < nRays; i++) _msg.ranges[i] = _obj.
getScanRange(i);
void resizeScan(const size_t len)
mrpt::system::TTimeStamp timestamp
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
mrpt::poses::CPose3D sensorPose
float getScanRange(const size_t i) const
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
GLdouble GLdouble GLdouble r
void setScanRange(const size_t i, const float val)
void setScanRangeValidity(const size_t i, const bool val)
void getSensorPose(mrpt::poses::CPose3D &out_sensorPose) const MRPT_OVERRIDE
size_t getScanSize() const