37 #include "sensor_msgs/LaserScan.h" 56 private_ns_.param(
"ignore_laser_skew", ignore_laser_skew_,
true);
59 filter_chain_.configure(
"filters", private_ns_);
62 if (ignore_laser_skew_)
67 skew_scan_sub_ = n_.subscribe(
"scan", 10, &LaserScanAssembler::scanCallback,
this);
78 return (scan.ranges.size ());
81 void ConvertToCloud(
const string& fixed_frame_id,
const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& cloud_out)
84 filter_chain_.update (scan_in, scan_filtered_);
87 if (ignore_laser_skew_)
89 projector_.projectLaser(scan_filtered_, cloud_out);
90 if (cloud_out.header.frame_id != fixed_frame_id)
91 tf_->transformPointCloud(fixed_frame_id, cloud_out, cloud_out);
99 projector_.transformLaserScanToPointCloud (fixed_frame_id, scan_filtered_, cloud_out, *tf_, mask);
106 if (!ignore_laser_skew_)
109 if (cur_tolerance > max_tolerance_)
111 ROS_DEBUG(
"Upping tf tolerance from [%.4fs] to [%.4fs]", max_tolerance_.toSec(), cur_tolerance.
toSec());
113 tf_filter_->setTolerance(cur_tolerance);
114 max_tolerance_ = cur_tolerance;
116 tf_filter_->add(laser_scan);
136 int main(
int argc,
char **argv)
138 ros::init(argc, argv,
"laser_scan_assembler");
ros::Duration max_tolerance_
sensor_msgs::LaserScan scan_filtered_
filters::FilterChain< sensor_msgs::LaserScan > filter_chain_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
laser_geometry::LaserProjection projector_
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
Maintains a history of point clouds and generates an aggregate point cloud upon request.
ros::Subscriber skew_scan_sub_
Maintains a history of laser scans and generates a point cloud upon request.
void ConvertToCloud(const string &fixed_frame_id, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out)
unsigned int GetPointsInScan(const sensor_msgs::LaserScan &scan)
Returns the number of points in the current scan.
void scanCallback(const sensor_msgs::LaserScanConstPtr &laser_scan)