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"
14 #include <Eigen/Dense>
15 #include <dynamic_reconfigure/server.h>
16 #include <ira_laser_tools/laserscan_multi_mergerConfig.h>
20 using namespace laserscan_multi_merger;
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);
43 void laserscan_topic_parser();
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;
75 istringstream iss(laserscan_topics);
77 copy(istream_iterator<string>(iss), istream_iterator<string>(), inserter<set<string>>(tokens, tokens.begin()));
78 vector<string> tmp_input_topics;
80 while (!tokens.empty())
86 for (
int i = 0; i < topics.size(); i++)
88 if (topics[i].
datatype ==
"sensor_msgs/LaserScan" && tokens.erase(topics[i].name) > 0)
90 tmp_input_topics.push_back(topics[i].name);
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());
100 if ((tmp_input_topics.size() != input_topics.size()) || !equal(tmp_input_topics.begin(), tmp_input_topics.end(), input_topics.begin()))
104 for (
int i = 0; i < scan_subscribers.size(); i++)
107 input_topics = tmp_input_topics;
109 if (input_topics.size() > 0)
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)
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] <<
" ";
123 ROS_INFO(
"Not subscribed to any topic.");
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);
142 this->laserscan_topic_parser();
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);
150 sensor_msgs::PointCloud tmpCloud1, tmpCloud2;
151 sensor_msgs::PointCloud2 tmpCloud3;
157 tfListener_.waitForTransform(scan->header.frame_id.c_str(), destination_frame.c_str(), scan->header.stamp,
ros::Duration(1));
159 tfListener_.transformPointCloud(destination_frame.c_str(), tmpCloud1, tmpCloud2);
166 for (
int i = 0; i < input_topics.size(); i++)
168 if (topic.compare(input_topics[i]) == 0)
172 clouds_modified[i] =
true;
178 for (
int i = 0; i < clouds_modified.size(); i++)
179 if (clouds_modified[i])
183 if (totalClouds == clouds_modified.size())
185 pcl::PCLPointCloud2 merged_cloud = clouds[0];
186 clouds_modified[0] =
false;
188 for (
int i = 1; i < clouds_modified.size(); i++)
190 #if PCL_VERSION_COMPARE(>=, 1, 10, 0)
191 pcl::concatenate(merged_cloud, clouds[i], merged_cloud);
195 clouds_modified[i] =
false;
198 point_cloud_publisher_.publish(merged_cloud);
200 Eigen::MatrixXf points;
201 getPointCloudAsEigen(merged_cloud, points);
203 pointcloud_to_laserscan(points, &merged_cloud);
209 sensor_msgs::LaserScanPtr output(
new sensor_msgs::LaserScan());
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;
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);
222 for (
int i = 0; i < points.cols(); i++)
224 const float &x = points(0, i);
225 const float &y = points(1, i);
226 const float &z = points(2, i);
228 if (std::isnan(x) || std::isnan(y) || std::isnan(z))
230 ROS_DEBUG(
"rejected for nan in point(%f, %f, %f)\n", x, y, z);
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_)
238 ROS_DEBUG(
"rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range_sq, range_min_sq_, x, y, z);
242 double angle = atan2(y, x);
243 if (angle < output->angle_min ||
angle > output->angle_max)
245 ROS_DEBUG(
"rejected for angle %f not in range (%f, %f)\n",
angle, output->angle_min, output->angle_max);
248 int index = (
angle - output->angle_min) / output->angle_increment;
250 if (output->ranges[index] * output->ranges[index] > range_sq)
251 output->ranges[index] = sqrt(range_sq);
254 laser_scan_publisher_.publish(output);
257 int main(
int argc,
char **argv)
259 ros::init(argc, argv,
"laser_multi_merger");
263 dynamic_reconfigure::Server<laserscan_multi_mergerConfig> server;
264 dynamic_reconfigure::Server<laserscan_multi_mergerConfig>::CallbackType
f;
267 server.setCallback(
f);