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 #include "laser_scan_sparsifier/laser_scan_sparsifier.h"
00031 
00032 namespace scan_tools {
00033 
00034 LaserScanSparsifier::LaserScanSparsifier(ros::NodeHandle nh, ros::NodeHandle nh_private):
00035   nh_(nh), 
00036   nh_private_(nh_private)
00037 {
00038   ROS_INFO ("Starting LaserScanSparsifier");
00039 
00040   
00041 
00042   if (!nh_private_.getParam ("step", step_))
00043     step_ = 2;
00044 
00045   ROS_ASSERT_MSG(step_ > 0,
00046     "step parameter is set to %, must be > 0", step_);
00047 
00048   
00049 
00050   scan_publisher_ = nh_.advertise<sensor_msgs::LaserScan>(
00051     "scan_sparse", 10);
00052 
00053   
00054 
00055   scan_subscriber_ = nh_.subscribe(
00056     "scan", 10, &LaserScanSparsifier::scanCallback, this);
00057 }
00058 
00059 LaserScanSparsifier::~LaserScanSparsifier ()
00060 {
00061   ROS_INFO ("Destroying LaserScanSparsifier");
00062 }
00063 
00064 void LaserScanSparsifier::scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg)
00065 {
00066   sensor_msgs::LaserScan::Ptr scan_sparse;
00067   scan_sparse = boost::make_shared<sensor_msgs::LaserScan>();
00068 
00069   
00070 
00071   scan_sparse->header          = scan_msg->header;
00072   scan_sparse->range_min       = scan_msg->range_min;
00073   scan_sparse->range_max       = scan_msg->range_max;
00074   scan_sparse->angle_min       = scan_msg->angle_min;
00075   scan_sparse->angle_increment = scan_msg->angle_increment * step_;
00076   scan_sparse->time_increment  = scan_msg->time_increment;
00077   scan_sparse->scan_time       = scan_msg->scan_time;
00078 
00079   
00080 
00081   unsigned int size_sparse = scan_msg->ranges.size() / step_;
00082   scan_sparse->ranges.resize(size_sparse);
00083 
00084   
00085 
00086   scan_sparse->angle_max = 
00087     scan_sparse->angle_min + (scan_sparse->angle_increment * (size_sparse - 1));
00088 
00089   for (unsigned int i = 0; i < size_sparse; i++)
00090   {
00091     scan_sparse->ranges[i] = scan_msg->ranges[i * step_];
00092     
00093   }
00094 
00095   scan_publisher_.publish(scan_sparse);
00096 }
00097 
00098 } 
00099