37 #include "sensor_msgs/LaserScan.h" 63 private_ns_.param(
"ignore_laser_skew", ignore_laser_skew_,
true);
66 filter_chain_.configure(
"filters", private_ns_);
76 return scan.ranges.size();
79 void ConvertToCloud(
const string& fixed_frame_id,
const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& cloud_out)
82 filter_chain_.update (scan_in, scan_filtered_);
85 if (ignore_laser_skew_)
87 projector_.projectLaser(scan_filtered_, cloud_out);
88 if (cloud_out.header.frame_id != fixed_frame_id)
89 tf_->transformPointCloud(fixed_frame_id, cloud_out, cloud_out);
94 projector_.transformLaserScanToPointCloud (fixed_frame_id, scan_filtered_, cloud_out, *tf_, mask);
112 int main(
int argc,
char **argv)
114 ros::init(argc, argv,
"laser_scan_assembler");
116 ROS_WARN(
"The laser_scan_assembler_srv is deprecated. Please switch to " 117 "using the laser_scan_assembler. Documentation is available at " 118 "http://www.ros.org/wiki/laser_assembler");
120 pc_assembler.
start();
Maintains a history of point clouds and generates an aggregate point cloud upon request.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Maintains a history of laser scans and generates a point cloud upon request.
ROSCPP_DECL void spin(Spinner &spinner)
unsigned int GetPointsInScan(const sensor_msgs::LaserScan &scan)
Returns the number of points in the current scan.
laser_geometry::LaserProjection projector_
filters::FilterChain< sensor_msgs::LaserScan > filter_chain_
sensor_msgs::LaserScan scan_filtered_
void ConvertToCloud(const string &fixed_frame_id, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out)
int main(int argc, char **argv)
void start()
Tells the assembler to start listening to input data It is possible that a derived class needs to ini...