2 #include <sensor_msgs/LaserScan.h> 3 #include <pluginlib/class_list_macros.h> 4 #include <sensor_msgs/point_cloud2_iterator.h> 5 #include <tf2_sensor_msgs/tf2_sensor_msgs.h> 30 int concurrency_level;
31 private_nh_.param<
int>(
"concurrency_level", concurrency_level, 1);
35 if (concurrency_level == 1)
37 nh_ = getNodeHandle();
41 nh_ = getMTNodeHandle();
45 if (concurrency_level > 0)
55 if (!target_frame_.empty())
57 tf2_.reset(
new tf2_ros::Buffer());
68 pub_ =
nh_.advertise<sensor_msgs::LaserScan>(
"scan", 10,
76 if (
pub_.getNumSubscribers() > 0 &&
sub_.getSubscriber().getNumPublishers() == 0)
78 NODELET_INFO(
"Got a subscriber to scan, starting subscriber to pointcloud");
86 if (
pub_.getNumSubscribers() == 0)
88 NODELET_INFO(
"No subscibers to scan, shutting down subscriber to pointcloud");
94 tf2_ros::filter_failure_reasons::FilterFailureReason reason)
96 NODELET_WARN_STREAM_THROTTLE(1.0,
"Can't transform pointcloud from frame " << cloud_msg->header.frame_id <<
" to " 97 <<
message_filter_->getTargetFramesString() <<
" at time " << cloud_msg->header.stamp <<
", reason: " << reason);
104 sensor_msgs::LaserScan output;
105 output.header = cloud_msg->header;
114 output.time_increment = 0.0;
120 uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
125 output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
129 output.ranges.assign(ranges_size, output.range_max +
inf_epsilon_);
132 sensor_msgs::PointCloud2ConstPtr cloud_out;
133 sensor_msgs::PointCloud2Ptr cloud;
136 if (!(output.header.frame_id == cloud_msg->header.frame_id))
140 cloud.reset(
new sensor_msgs::PointCloud2);
144 catch (tf2::TransformException &ex)
146 NODELET_ERROR_STREAM(
"Transform failure: " << ex.what());
152 cloud_out = cloud_msg;
156 for (sensor_msgs::PointCloud2ConstIterator<float>
157 iter_x(*cloud_out,
"x"), iter_y(*cloud_out,
"y"), iter_z(*cloud_out,
"z");
158 iter_x != iter_x.end();
159 ++iter_x, ++iter_y, ++iter_z)
162 if (std::isnan(*iter_x) || std::isnan(*iter_y) || std::isnan(*iter_z))
164 NODELET_DEBUG(
"rejected for nan in point(%f, %f, %f)\n", *iter_x, *iter_y, *iter_z);
174 double range = hypot(*iter_x, *iter_y);
177 NODELET_DEBUG(
"rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range,
range_min_, *iter_x, *iter_y,
182 double angle = atan2(*iter_y, *iter_x);
183 if (angle < output.angle_min || angle > output.angle_max)
185 NODELET_DEBUG(
"rejected for angle %f not in range (%f, %f)\n", angle, output.angle_min, output.angle_max);
190 int index = (angle - output.angle_min) / output.angle_increment;
191 if (range < output.ranges[index])
193 output.ranges[index] = range;
197 pub_.publish(output);
boost::shared_ptr< tf2_ros::Buffer > tf2_
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > MessageFilter
boost::shared_ptr< MessageFilter > message_filter_
PointCloudToLaserScanNodelet()
unsigned int input_queue_size_
ros::NodeHandle private_nh_
std::string target_frame_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_
boost::mutex connect_mutex_