point_cloud_to_laserscan.cpp
Go to the documentation of this file.
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>
6 
8 {
9 
11 
13  {
14  boost::mutex::scoped_lock lock(connect_mutex_);
15  private_nh_ = getPrivateNodeHandle();
16 
17  private_nh_.param<std::string>("target_frame", target_frame_, "");
18  private_nh_.param<double>("transform_tolerance", tolerance_, 0.01);
19  private_nh_.param<double>("min_height", min_height_, std::numeric_limits<double>::min());
20  private_nh_.param<double>("max_height", max_height_, std::numeric_limits<double>::max());
21 
22  private_nh_.param<double>("angle_min", angle_min_, - M_PI);
23  private_nh_.param<double>("angle_max", angle_max_, M_PI);
24  private_nh_.param<double>("angle_increment", angle_increment_, M_PI / 180.0);
25  private_nh_.param<double>("scan_time", scan_time_, 1.0 / 30.0);
26  private_nh_.param<double>("range_min", range_min_, 0.0);
27  private_nh_.param<double>("range_max", range_max_, std::numeric_limits<double>::max());
28  private_nh_.param<double>("inf_epsilon", inf_epsilon_, 1.0);
29 
30  int concurrency_level;
31  private_nh_.param<int>("concurrency_level", concurrency_level, 1);
32  private_nh_.param<bool>("use_inf", use_inf_, true);
33 
34  //Check if explicitly single threaded, otherwise, let nodelet manager dictate thread pool size
35  if (concurrency_level == 1)
36  {
37  nh_ = getNodeHandle();
38  }
39  else
40  {
41  nh_ = getMTNodeHandle();
42  }
43 
44  // Only queue one pointcloud per running thread
45  if (concurrency_level > 0)
46  {
47  input_queue_size_ = concurrency_level;
48  }
49  else
50  {
51  input_queue_size_ = boost::thread::hardware_concurrency();
52  }
53 
54  // if pointcloud target frame specified, we need to filter by transform availability
55  if (!target_frame_.empty())
56  {
57  tf2_.reset(new tf2_ros::Buffer());
58  tf2_listener_.reset(new tf2_ros::TransformListener(*tf2_));
59  message_filter_.reset(new MessageFilter(sub_, *tf2_, target_frame_, input_queue_size_, nh_));
60  message_filter_->registerCallback(boost::bind(&PointCloudToLaserScanNodelet::cloudCb, this, _1));
61  message_filter_->registerFailureCallback(boost::bind(&PointCloudToLaserScanNodelet::failureCb, this, _1, _2));
62  }
63  else // otherwise setup direct subscription
64  {
65  sub_.registerCallback(boost::bind(&PointCloudToLaserScanNodelet::cloudCb, this, _1));
66  }
67 
68  pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 10,
69  boost::bind(&PointCloudToLaserScanNodelet::connectCb, this),
70  boost::bind(&PointCloudToLaserScanNodelet::disconnectCb, this));
71  }
72 
74  {
75  boost::mutex::scoped_lock lock(connect_mutex_);
76  if (pub_.getNumSubscribers() > 0 && sub_.getSubscriber().getNumPublishers() == 0)
77  {
78  NODELET_INFO("Got a subscriber to scan, starting subscriber to pointcloud");
79  sub_.subscribe(nh_, "cloud_in", input_queue_size_);
80  }
81  }
82 
84  {
85  boost::mutex::scoped_lock lock(connect_mutex_);
86  if (pub_.getNumSubscribers() == 0)
87  {
88  NODELET_INFO("No subscibers to scan, shutting down subscriber to pointcloud");
89  sub_.unsubscribe();
90  }
91  }
92 
93  void PointCloudToLaserScanNodelet::failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg,
94  tf2_ros::filter_failure_reasons::FilterFailureReason reason)
95  {
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);
98  }
99 
100  void PointCloudToLaserScanNodelet::cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
101  {
102 
103  //build laserscan output
104  sensor_msgs::LaserScan output;
105  output.header = cloud_msg->header;
106  if (!target_frame_.empty())
107  {
108  output.header.frame_id = target_frame_;
109  }
110 
111  output.angle_min = angle_min_;
112  output.angle_max = angle_max_;
113  output.angle_increment = angle_increment_;
114  output.time_increment = 0.0;
115  output.scan_time = scan_time_;
116  output.range_min = range_min_;
117  output.range_max = range_max_;
118 
119  //determine amount of rays to create
120  uint32_t ranges_size = std::ceil((output.angle_max - output.angle_min) / output.angle_increment);
121 
122  //determine if laserscan rays with no obstacle data will evaluate to infinity or max_range
123  if (use_inf_)
124  {
125  output.ranges.assign(ranges_size, std::numeric_limits<double>::infinity());
126  }
127  else
128  {
129  output.ranges.assign(ranges_size, output.range_max + inf_epsilon_);
130  }
131 
132  sensor_msgs::PointCloud2ConstPtr cloud_out;
133  sensor_msgs::PointCloud2Ptr cloud;
134 
135  // Transform cloud if necessary
136  if (!(output.header.frame_id == cloud_msg->header.frame_id))
137  {
138  try
139  {
140  cloud.reset(new sensor_msgs::PointCloud2);
141  tf2_->transform(*cloud_msg, *cloud, target_frame_, ros::Duration(tolerance_));
142  cloud_out = cloud;
143  }
144  catch (tf2::TransformException &ex)
145  {
146  NODELET_ERROR_STREAM("Transform failure: " << ex.what());
147  return;
148  }
149  }
150  else
151  {
152  cloud_out = cloud_msg;
153  }
154 
155  // Iterate through pointcloud
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)
160  {
161 
162  if (std::isnan(*iter_x) || std::isnan(*iter_y) || std::isnan(*iter_z))
163  {
164  NODELET_DEBUG("rejected for nan in point(%f, %f, %f)\n", *iter_x, *iter_y, *iter_z);
165  continue;
166  }
167 
168  if (*iter_z > max_height_ || *iter_z < min_height_)
169  {
170  NODELET_DEBUG("rejected for height %f not in range (%f, %f)\n", *iter_z, min_height_, max_height_);
171  continue;
172  }
173 
174  double range = hypot(*iter_x, *iter_y);
175  if (range < range_min_)
176  {
177  NODELET_DEBUG("rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range, range_min_, *iter_x, *iter_y,
178  *iter_z);
179  continue;
180  }
181 
182  double angle = atan2(*iter_y, *iter_x);
183  if (angle < output.angle_min || angle > output.angle_max)
184  {
185  NODELET_DEBUG("rejected for angle %f not in range (%f, %f)\n", angle, output.angle_min, output.angle_max);
186  continue;
187  }
188 
189  //overwrite range at laserscan ray if new range is smaller
190  int index = (angle - output.angle_min) / output.angle_increment;
191  if (range < output.ranges[index])
192  {
193  output.ranges[index] = range;
194  }
195 
196  }
197  pub_.publish(output);
198  }
199 
200 }
201 
PLUGINLIB_EXPORT_CLASS(pses_kinect_utilities::MedianFilterNodelet, nodelet::Nodelet)
void failureCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > MessageFilter
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
void cloudCb(const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
boost::shared_ptr< tf2_ros::TransformListener > tf2_listener_


pses_kinect_utilities
Author(s): Nicolas Acero
autogenerated on Sun Nov 26 2017 19:23:52