36 nh_private_(nh_private)
38 ROS_INFO (
"Starting LaserScanSparsifier");
46 "step parameter is set to %d, must be > 0",
step_);
61 ROS_INFO (
"Destroying LaserScanSparsifier");
66 sensor_msgs::LaserScan::Ptr scan_sparse;
67 scan_sparse = boost::make_shared<sensor_msgs::LaserScan>();
71 scan_sparse->header = scan_msg->header;
72 scan_sparse->range_min = scan_msg->range_min;
73 scan_sparse->range_max = scan_msg->range_max;
74 scan_sparse->angle_min = scan_msg->angle_min;
75 scan_sparse->angle_increment = scan_msg->angle_increment *
step_;
76 scan_sparse->time_increment = scan_msg->time_increment;
77 scan_sparse->scan_time = scan_msg->scan_time;
81 unsigned int size_sparse = scan_msg->ranges.size() /
step_;
82 scan_sparse->ranges.resize(size_sparse);
86 scan_sparse->angle_max =
87 scan_sparse->angle_min + (scan_sparse->angle_increment * (size_sparse - 1));
89 for (
unsigned int i = 0; i < size_sparse; i++)
91 scan_sparse->ranges[i] = scan_msg->ranges[i *
step_];