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


ira_laser_tools
Author(s):
autogenerated on Wed Mar 2 2022 00:28:44