laserscan_multi_merger.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <string.h>
4 #include <pcl_ros/transforms.h>
6 #include <pcl/conversions.h>
7 #include <pcl/point_cloud.h>
8 #include <pcl/point_types.h>
9 #include <pcl/io/pcd_io.h>
10 #include <sensor_msgs/PointCloud.h>
11 #include <sensor_msgs/PointCloud2.h>
13 #include "sensor_msgs/LaserScan.h"
14 #include "pcl_ros/point_cloud.h"
15 #include <Eigen/Dense>
16 #include <dynamic_reconfigure/server.h>
17 #include <ira_laser_tools/laserscan_multi_mergerConfig.h>
18 
19 using namespace std;
20 using namespace pcl;
21 using namespace laserscan_multi_merger;
22 
24 {
25 public:
27  void scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan, std::string topic);
28  void pointcloud_to_laserscan(Eigen::MatrixXf points, pcl::PCLPointCloud2 *merged_cloud);
29  void reconfigureCallback(laserscan_multi_mergerConfig &config, uint32_t level);
30 
31 private:
35 
38  vector<ros::Subscriber> scan_subscribers;
39  vector<bool> clouds_modified;
40 
41  vector<pcl::PCLPointCloud2> clouds;
42  vector<string> input_topics;
43 
44  void laserscan_topic_parser();
45 
46  double angle_min;
47  double angle_max;
50  double scan_time;
51  double range_min;
52  double range_max;
53 
58 };
59 
60 void LaserscanMerger::reconfigureCallback(laserscan_multi_mergerConfig &config, uint32_t level)
61 {
62  this->angle_min = config.angle_min;
63  this->angle_max = config.angle_max;
64  this->angle_increment = config.angle_increment;
65  this->time_increment = config.time_increment;
66  this->scan_time = config.scan_time;
67  this->range_min = config.range_min;
68  this->range_max = config.range_max;
69 }
70 
72 {
73  // LaserScan topics to subscribe
75  ros::master::getTopics(topics);
76 
77  istringstream iss(laserscan_topics);
78  vector<string> tokens;
79  copy(istream_iterator<string>(iss), istream_iterator<string>(), back_inserter<vector<string> >(tokens));
80  vector<string> tmp_input_topics;
81  for(int i=0;i<tokens.size();++i)
82  {
83  for(int j=0;j<topics.size();++j)
84  {
85  if( (tokens[i].compare(topics[j].name) == 0) && (topics[j].datatype.compare("sensor_msgs/LaserScan") == 0) )
86  {
87  tmp_input_topics.push_back(topics[j].name);
88  }
89  }
90  }
91 
92  sort(tmp_input_topics.begin(),tmp_input_topics.end());
93  std::vector<string>::iterator last = std::unique(tmp_input_topics.begin(), tmp_input_topics.end());
94  tmp_input_topics.erase(last, tmp_input_topics.end());
95 
96 
97  // Do not re-subscribe if the topics are the same
98  if( (tmp_input_topics.size() != input_topics.size()) || !equal(tmp_input_topics.begin(),tmp_input_topics.end(),input_topics.begin()))
99  {
100 
101  // Unsubscribe from previous topics
102  for(int i=0; i<scan_subscribers.size(); ++i)
103  scan_subscribers[i].shutdown();
104 
105  input_topics = tmp_input_topics;
106  if(input_topics.size() > 0)
107  {
108  scan_subscribers.resize(input_topics.size());
109  clouds_modified.resize(input_topics.size());
110  clouds.resize(input_topics.size());
111  ROS_INFO("Subscribing to topics\t%ld", scan_subscribers.size());
112  for(int i=0; i<input_topics.size(); ++i)
113  {
114  scan_subscribers[i] = node_.subscribe<sensor_msgs::LaserScan> (input_topics[i].c_str(), 1, boost::bind(&LaserscanMerger::scanCallback,this, _1, input_topics[i]));
115  clouds_modified[i] = false;
116  cout << input_topics[i] << " ";
117  }
118  }
119  else
120  ROS_INFO("Not subscribed to any topic.");
121  }
122 }
123 
125 {
126  ros::NodeHandle nh("~");
127 
128  nh.param<std::string>("destination_frame", destination_frame, "cart_frame");
129  nh.param<std::string>("cloud_destination_topic", cloud_destination_topic, "/merged_cloud");
130  nh.param<std::string>("scan_destination_topic", scan_destination_topic, "/scan_multi");
131  nh.param<std::string>("laserscan_topics", laserscan_topics, "");
132  nh.param("angle_min", angle_min, -2.36);
133  nh.param("angle_max", angle_max, 2.36);
134  nh.param("angle_increment", angle_increment, 0.0058);
135  nh.param("scan_time", scan_time, 0.0333333);
136  nh.param("range_min", range_min, 0.45);
137  nh.param("range_max", range_max, 25.0);
138 
139  this->laserscan_topic_parser();
140 
141  point_cloud_publisher_ = node_.advertise<sensor_msgs::PointCloud2> (cloud_destination_topic.c_str(), 1, false);
142  laser_scan_publisher_ = node_.advertise<sensor_msgs::LaserScan> (scan_destination_topic.c_str(), 1, false);
143 
144 }
145 
146 void LaserscanMerger::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan, std::string topic)
147 {
148  sensor_msgs::PointCloud tmpCloud1,tmpCloud2;
149  sensor_msgs::PointCloud2 tmpCloud3;
150 
151  // Verify that TF knows how to transform from the received scan to the destination scan frame
152  tfListener_.waitForTransform(scan->header.frame_id.c_str(), destination_frame.c_str(), scan->header.stamp, ros::Duration(1));
153  projector_.transformLaserScanToPointCloud(scan->header.frame_id, *scan, tmpCloud1, tfListener_, laser_geometry::channel_option::Distance);
154  try
155  {
156  tfListener_.transformPointCloud(destination_frame.c_str(), tmpCloud1, tmpCloud2);
157  }catch (tf::TransformException ex){ROS_ERROR("%s",ex.what());return;}
158 
159  for(int i=0; i<input_topics.size(); ++i)
160  {
161  if(topic.compare(input_topics[i]) == 0)
162  {
163  sensor_msgs::convertPointCloudToPointCloud2(tmpCloud2,tmpCloud3);
164  pcl_conversions::toPCL(tmpCloud3, clouds[i]);
165  clouds_modified[i] = true;
166  }
167  }
168 
169  // Count how many scans we have
170  int totalClouds = 0;
171  for(int i=0; i<clouds_modified.size(); ++i)
172  if(clouds_modified[i])
173  ++totalClouds;
174 
175  // Go ahead only if all subscribed scans have arrived
176  if(totalClouds == clouds_modified.size())
177  {
178  pcl::PCLPointCloud2 merged_cloud = clouds[0];
179  clouds_modified[0] = false;
180 
181  for(int i=1; i<clouds_modified.size(); ++i)
182  {
183  pcl::concatenatePointCloud(merged_cloud, clouds[i], merged_cloud);
184  clouds_modified[i] = false;
185  }
186 
187  point_cloud_publisher_.publish(merged_cloud);
188 
189  Eigen::MatrixXf points;
190  getPointCloudAsEigen(merged_cloud,points);
191 
192  pointcloud_to_laserscan(points, &merged_cloud);
193  }
194 }
195 
196 void LaserscanMerger::pointcloud_to_laserscan(Eigen::MatrixXf points, pcl::PCLPointCloud2 *merged_cloud)
197 {
198  sensor_msgs::LaserScanPtr output(new sensor_msgs::LaserScan());
199  output->header = pcl_conversions::fromPCL(merged_cloud->header);
200  output->header.frame_id = destination_frame.c_str();
201  output->header.stamp = ros::Time::now(); //fixes #265
202  output->angle_min = this->angle_min;
203  output->angle_max = this->angle_max;
204  output->angle_increment = this->angle_increment;
205  output->time_increment = this->time_increment;
206  output->scan_time = this->scan_time;
207  output->range_min = this->range_min;
208  output->range_max = this->range_max;
209 
210  uint32_t ranges_size = std::ceil((output->angle_max - output->angle_min) / output->angle_increment);
211  output->ranges.assign(ranges_size, output->range_max + 1.0);
212 
213  for(int i=0; i<points.cols(); i++)
214  {
215  const float &x = points(0,i);
216  const float &y = points(1,i);
217  const float &z = points(2,i);
218 
219  if ( std::isnan(x) || std::isnan(y) || std::isnan(z) )
220  {
221  ROS_DEBUG("rejected for nan in point(%f, %f, %f)\n", x, y, z);
222  continue;
223  }
224 
225  double range_sq = y*y+x*x;
226  double range_min_sq_ = output->range_min * output->range_min;
227  if (range_sq < range_min_sq_) {
228  ROS_DEBUG("rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range_sq, range_min_sq_, x, y, z);
229  continue;
230  }
231 
232  double angle = atan2(y, x);
233  if (angle < output->angle_min || angle > output->angle_max)
234  {
235  ROS_DEBUG("rejected for angle %f not in range (%f, %f)\n", angle, output->angle_min, output->angle_max);
236  continue;
237  }
238  int index = (angle - output->angle_min) / output->angle_increment;
239 
240 
241  if (output->ranges[index] * output->ranges[index] > range_sq)
242  output->ranges[index] = sqrt(range_sq);
243  }
244 
245  laser_scan_publisher_.publish(output);
246 }
247 
248 int main(int argc, char** argv)
249 {
250  ros::init(argc, argv, "laser_multi_merger");
251 
252  LaserscanMerger _laser_merger;
253 
254  dynamic_reconfigure::Server<laserscan_multi_mergerConfig> server;
255  dynamic_reconfigure::Server<laserscan_multi_mergerConfig>::CallbackType f;
256 
257  f = boost::bind(&LaserscanMerger::reconfigureCallback,&_laser_merger, _1, _2);
258  server.setCallback(f);
259 
260  ros::spin();
261 
262  return 0;
263 }
vector< bool > clouds_modified
tf::TransformListener tfListener_
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
laser_geometry::LaserProjection projector_
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
vector< ros::Subscriber > scan_subscribers
std::vector< TopicInfo > V_TopicInfo
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
int main(int argc, char **argv)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
vector< string > input_topics
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
void reconfigureCallback(laserscan_multi_mergerConfig &config, uint32_t level)
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan, std::string topic)
static Time now()
void pointcloud_to_laserscan(Eigen::MatrixXf points, pcl::PCLPointCloud2 *merged_cloud)
ros::Publisher point_cloud_publisher_
ros::Publisher laser_scan_publisher_
#define ROS_ERROR(...)
vector< pcl::PCLPointCloud2 > clouds
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
#define ROS_DEBUG(...)


ira_laser_tools
Author(s):
autogenerated on Fri Feb 14 2020 09:55:50