44 #include <sensor_msgs/LaserScan.h>
73 int concurrency_level;
78 if (concurrency_level == 1)
88 if (concurrency_level > 0)
120 NODELET_INFO(
"Got a subscriber to scan, starting subscriber to pointcloud");
130 NODELET_INFO(
"No subscibers to scan, shutting down subscriber to pointcloud");
140 <<
" at time " << cloud_msg->header.stamp
141 <<
", reason: " << reason);
147 sensor_msgs::LaserScan output;
148 output.header = cloud_msg->header;
157 output.time_increment = 0.0;
163 uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
168 output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
172 output.ranges.assign(ranges_size, output.range_max +
inf_epsilon_);
175 sensor_msgs::PointCloud2ConstPtr cloud_out;
176 sensor_msgs::PointCloud2Ptr cloud;
179 if (!(output.header.frame_id == cloud_msg->header.frame_id))
183 cloud.reset(
new sensor_msgs::PointCloud2);
195 cloud_out = cloud_msg;
200 iter_z(*cloud_out,
"z");
201 iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
203 if (std::isnan(*iter_x) || std::isnan(*iter_y) || std::isnan(*iter_z))
205 NODELET_DEBUG(
"rejected for nan in point(%f, %f, %f)\n", *iter_x, *iter_y, *iter_z);
215 double range = hypot(*iter_x, *iter_y);
229 double angle = atan2(*iter_y, *iter_x);
230 if (angle < output.angle_min || angle > output.angle_max)
232 NODELET_DEBUG(
"rejected for angle %f not in range (%f, %f)\n",
angle, output.angle_min, output.angle_max);
237 int index = (
angle - output.angle_min) / output.angle_increment;
238 if (range < output.ranges[index])
240 output.ranges[index] = range;