6 #include <pcl/conversions.h>
7 #include <pcl/point_cloud.h>
8 #include <pcl/point_types.h>
9 #include <pcl/io/pcd_io.h>
11 #include "sensor_msgs/LaserScan.h"
13 #include <Eigen/Dense>
14 #include <dynamic_reconfigure/server.h>
15 #include <ira_laser_tools/laserscan_virtualizerConfig.h>
21 using namespace laserscan_virtualizer;
27 void scanCallback(
const sensor_msgs::LaserScan::ConstPtr &scan, std::string topic);
28 void pointcloud_to_laserscan(Eigen::MatrixXf points, pcl::PCLHeader scan_header,
int pub_index);
29 void pointCloudCallback(
const sensor_msgs::PointCloud2::ConstPtr &pcl_in);
30 void reconfigureCallback(laserscan_virtualizerConfig &config, uint32_t level);
41 void virtual_laser_scan_parser();
60 this->angle_min = config.angle_min;
61 this->angle_max = config.angle_max;
62 this->angle_increment = config.angle_increment;
63 this->time_increment = config.time_increment;
64 this->scan_time = config.scan_time;
65 this->range_min = config.range_min;
66 this->range_max = config.range_max;
72 istringstream iss(virtual_laser_scan);
73 vector<string> tokens;
74 copy(istream_iterator<string>(iss), istream_iterator<string>(), back_inserter<vector<string>>(tokens));
76 vector<string> tmp_output_frames;
78 for (
int i = 0; i < tokens.size(); i++)
84 cout <<
"Adding: " << tokens[i] << endl;
85 tmp_output_frames.push_back(tokens[i]);
88 cout <<
"Can't transform: '" << tokens[i] +
"' to '" << base_frame <<
"'" << endl;
92 sort(tmp_output_frames.begin(), tmp_output_frames.end());
93 std::vector<string>::iterator last = std::unique(tmp_output_frames.begin(), tmp_output_frames.end());
94 tmp_output_frames.erase(last, tmp_output_frames.end());
97 if ((tmp_output_frames.size() != output_frames.size()) || !equal(tmp_output_frames.begin(), tmp_output_frames.end(), output_frames.begin()))
100 for (
int i = 0; i < virtual_scan_publishers.size(); i++)
101 virtual_scan_publishers[i].
shutdown();
105 output_frames = tmp_output_frames;
106 if (output_frames.size() > 0)
108 virtual_scan_publishers.resize(output_frames.size());
109 ROS_INFO(
"Publishing: %ld virtual scans", virtual_scan_publishers.size());
110 cout <<
"Advertising topics: " << endl;
111 for (
int i = 0; i < output_frames.size(); ++i)
113 if (output_laser_topic.empty())
115 virtual_scan_publishers[i] = node_.advertise<sensor_msgs::LaserScan>(output_frames[i].c_str(), 1);
116 cout <<
"\t\t" << output_frames[i] <<
" on topic " << output_frames[i].c_str() << endl;
120 virtual_scan_publishers[i] = node_.advertise<sensor_msgs::LaserScan>(output_laser_topic.c_str(), 1);
121 cout <<
"\t\t" << output_frames[i] <<
" on topic " << output_laser_topic.c_str() << endl;
126 ROS_INFO(
"Not publishing to any topic.");
135 if (!nh.
getParam(
"/laserscan_virtualizer/base_frame", base_frame))
136 base_frame =
"/cart_frame";
138 if (!nh.
getParam(
"/laserscan_virtualizer/cloud_topic", cloud_topic))
139 cloud_topic =
"/cloud_pcd";
141 nh.
getParam(
"/laserscan_virtualizer/output_laser_topic", output_laser_topic);
142 nh.
getParam(
"/laserscan_virtualizer/virtual_laser_scan", virtual_laser_scan);
144 this->virtual_laser_scan_parser();
152 if (cloud_frame.empty())
154 cloud_frame = (*pcl_in).header.frame_id;
155 transform_.resize(output_frames.size());
156 for (
int i = 0; i < output_frames.size(); i++)
158 tfListener_.lookupTransform(output_frames[i], cloud_frame,
ros::Time(0), transform_[i]);
161 for (
int i = 0; i < output_frames.size(); i++)
164 pcl::PCLPointCloud2 tmpPcl2;
167 pcl::fromPCLPointCloud2(tmpPcl2, tmpPcl);
171 string tmpFrame = output_frames[i];
172 pcl_out.header = tmpPcl.header;
176 pcl_out.header.frame_id = tmpFrame;
179 Eigen::MatrixXf tmpEigenMatrix;
180 pcl::toPCLPointCloud2(pcl_out, tmpPcl2);
181 pcl::getPointCloudAsEigen(tmpPcl2, tmpEigenMatrix);
184 pointcloud_to_laserscan(tmpEigenMatrix, pcl_out.header, i);
190 sensor_msgs::LaserScanPtr output(
new sensor_msgs::LaserScan());
192 output->angle_min = this->angle_min;
193 output->angle_max = this->angle_max;
194 output->angle_increment = this->angle_increment;
195 output->time_increment = this->time_increment;
196 output->scan_time = this->scan_time;
197 output->range_min = this->range_min;
198 output->range_max = this->range_max;
200 uint32_t ranges_size = std::ceil((output->angle_max - output->angle_min) / output->angle_increment);
201 output->ranges.assign(ranges_size, output->range_max + 1.0);
203 for (
int i = 0; i < points.cols(); i++)
205 const float &x = points(0, i);
206 const float &y = points(1, i);
207 const float &z = points(2, i);
209 if (std::isnan(x) || std::isnan(y) || std::isnan(z))
211 ROS_DEBUG(
"rejected for nan in point(%f, %f, %f)\n", x, y, z);
220 double range_sq = pow(y, 2) + pow(x, 2);
221 double range_min_sq_ = output->range_min * output->range_min;
222 if (range_sq < range_min_sq_)
224 ROS_DEBUG(
"rejected for range %f below minimum value %f. Point: (%f, %f, %f)", range_sq, range_min_sq_, x, y, z);
228 double angle = atan2(y, x);
229 if (angle < output->angle_min ||
angle > output->angle_max)
231 ROS_DEBUG(
"rejected for angle %f not in range (%f, %f)\n",
angle, output->angle_min, output->angle_max);
234 int index = (
angle - output->angle_min) / output->angle_increment;
236 if (output->ranges[index] * output->ranges[index] > range_sq)
237 output->ranges[index] = sqrt(range_sq);
240 virtual_scan_publishers[pub_index].publish(output);
243 int main(
int argc,
char **argv)
245 ros::init(argc, argv,
"laserscan_virtualizer");
249 dynamic_reconfigure::Server<laserscan_virtualizerConfig> server;
250 dynamic_reconfigure::Server<laserscan_virtualizerConfig>::CallbackType
f;
253 server.setCallback(
f);