39 sensor_msgs::LaserScanPtr out(
new sensor_msgs::LaserScan());
41 out->ranges.resize(msg.ranges.size());
42 if(msg.ranges.size() == msg.intensities.size()){
43 out->intensities.resize(msg.intensities.size());
46 for(
size_t i = 0; i < out->ranges.size(); i++){
48 if(out->intensities.size() > 0){
49 if(msg.intensities[i].echoes.size() > 0){
50 out->intensities[i] = msg.intensities[i].echoes[index];
52 out->intensities[i] = 0.0;
60 sensor_msgs::LaserScanPtr out(
new sensor_msgs::LaserScan());
62 out->ranges.resize(msg.ranges.size());
63 if(msg.ranges.size() == msg.intensities.size()){
64 out->intensities.resize(msg.intensities.size());
66 for(
size_t i = 0; i < out->ranges.size(); i++){
67 size_t index =
getLastValue(msg.ranges[i], out->ranges[i]);
68 if(out->intensities.size() > 0){
69 if(msg.intensities[i].echoes.size() > 0){
70 out->intensities[i] = msg.intensities[i].echoes[index];
72 out->intensities[i] = 0.0;
80 sensor_msgs::LaserScanPtr out(
new sensor_msgs::LaserScan());
82 if(msg.ranges.size() == msg.intensities.size()){
83 out->ranges.resize(msg.ranges.size());
84 out->intensities.resize(msg.intensities.size());
87 ss <<
"getMostIntenseScan::Size of ranges does not equal size of intensities, cannot create scan.";
88 throw std::runtime_error(ss.str());
90 for(
size_t i = 0; i < out->intensities.size(); i++){
91 getMostIntenseValue(msg.ranges[i], msg.intensities[i], out->ranges[i], out->intensities[i]);
97 out.header = msg.header;
98 out.angle_min = msg.angle_min;
99 out.angle_max = msg.angle_max;
100 out.angle_increment = msg.angle_increment;
101 out.time_increment = msg.time_increment;
102 out.scan_time = msg.scan_time;
103 out.range_min = msg.range_min;
104 out.range_max = msg.range_max;
109 if(ranges.echoes.size() > 0){
111 range = ranges.echoes[index];
115 range = std::numeric_limits<float>::quiet_NaN();
121 if(ranges.echoes.size() > 0){
122 size_t index = ranges.echoes.size()-1;
123 range = ranges.echoes[index];
127 range = std::numeric_limits<float>::quiet_NaN();
132 if(intensities.echoes.size() == 0){
133 range = std::numeric_limits<float>::quiet_NaN();
138 std::vector<float>::const_iterator max_iter = std::max_element(intensities.echoes.begin(), intensities.echoes.end());
139 size_t index = std::distance(intensities.echoes.begin(), max_iter);
141 if(ranges.echoes.size() > 0){
142 range = ranges.echoes[index];
143 intensity = *max_iter;
145 range = std::numeric_limits<float>::quiet_NaN();
static sensor_msgs::LaserScanPtr getFirstScan(const sensor_msgs::MultiEchoLaserScan &msg)
static sensor_msgs::LaserScanPtr getMostIntenseScan(const sensor_msgs::MultiEchoLaserScan &msg)
static size_t getLastValue(const sensor_msgs::LaserEcho &ranges, float &range)
static sensor_msgs::LaserScanPtr getLastScan(const sensor_msgs::MultiEchoLaserScan &msg)
static void fillLaserScan(const sensor_msgs::MultiEchoLaserScan &msg, sensor_msgs::LaserScan &out)
I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest)...
static size_t getFirstValue(const sensor_msgs::LaserEcho &ranges, float &range)
I'm assuming all laserscanners/drivers output the ranges in order received (shortest to longest)...
static void getMostIntenseValue(const sensor_msgs::LaserEcho &ranges, const sensor_msgs::LaserEcho &intensities, float &range, float &intensity)