Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045 #include "laser_scan_densifier/laser_scan_densifier.h"
00046
00047 namespace scan_tools {
00048
00049 LaserScanDensifier::LaserScanDensifier(ros::NodeHandle nh, ros::NodeHandle nh_private):
00050 nh_(nh),
00051 nh_private_(nh_private)
00052 {
00053 ROS_INFO ("Starting LaserScanDensifier");
00054
00055
00056
00057 nh_private_.param("step", step_, 2);
00058 nh_private_.param("mode", mode_, 0);
00059
00060 ROS_ASSERT_MSG(step_ > 0, "step parameter is set to %, must be > 0", step_);
00061
00062 switch(mode_) {
00063 case 0: ROS_INFO("LaserScanDensifier started with mode %d: copy data points", mode_);
00064 break;
00065 case 1: ROS_INFO("LaserScanDensifier started with mode %d: interpolate data points", mode_);
00066 break;
00067 default: ROS_WARN("LaserScanDensifier started with unsupported mode %d. Defaulting to mode 0: copy data points", mode_);
00068 mode_ = 0;
00069 break;
00070 }
00071
00072
00073
00074 scan_publisher_ = nh_.advertise<sensor_msgs::LaserScan>("scan_dense", 1);
00075
00076
00077
00078 scan_subscriber_ = nh_.subscribe("scan", 1, &LaserScanDensifier::scanCallback, this);
00079 }
00080
00081 LaserScanDensifier::~LaserScanDensifier ()
00082 {
00083 ROS_INFO ("Destroying LaserScanDensifier");
00084 }
00085
00086 void LaserScanDensifier::scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg)
00087 {
00088 sensor_msgs::LaserScan::Ptr scan_dense;
00089 scan_dense = boost::make_shared<sensor_msgs::LaserScan>();
00090
00091
00092
00093 scan_dense->header = scan_msg->header;
00094 scan_dense->range_min = scan_msg->range_min;
00095 scan_dense->range_max = scan_msg->range_max;
00096 scan_dense->angle_min = scan_msg->angle_min;
00097 scan_dense->angle_max = scan_msg->angle_max;
00098 scan_dense->angle_increment = scan_msg->angle_increment / step_;
00099 scan_dense->time_increment = scan_msg->time_increment;
00100 scan_dense->scan_time = scan_msg->scan_time;
00101
00102 scan_dense->ranges.clear();
00103 scan_dense->intensities.clear();
00104
00105 for (size_t i = 0; i < scan_msg->ranges.size()-1; i++)
00106 {
00107 switch (mode_) {
00108 case 0: {
00109 scan_dense->ranges.insert(scan_dense->ranges.end(), step_, scan_msg->ranges[i]);
00110 scan_dense->intensities.insert(scan_dense->intensities.end(), step_, scan_msg->intensities[i]);
00111 break;
00112 }
00113 case 1: {
00114 double delta_range = (scan_msg->ranges[i+1]-scan_msg->ranges[i])/step_;
00115 double delta_intensities = (scan_msg->intensities[i+1]-scan_msg->intensities[i])/step_;
00116 for (int k = 0; k < step_; k++) {
00117 scan_dense->ranges.insert(scan_dense->ranges.end(), 1, scan_msg->ranges[i]+k*delta_range);
00118 scan_dense->intensities.insert(scan_dense->intensities.end(), 1, scan_msg->intensities[i]+k*delta_intensities);
00119 }
00120 break;
00121 }
00122 }
00123 }
00124
00125 scan_dense->ranges.push_back(scan_msg->ranges.back());
00126 scan_dense->intensities.push_back(scan_msg->intensities.back());
00127
00128 scan_publisher_.publish(scan_dense);
00129 }
00130
00131 }
00132