65 return scan.points.size() ;
68 void ConvertToCloud(
const string& fixed_frame_id,
const sensor_msgs::PointCloud& scan_in, sensor_msgs::PointCloud& cloud_out)
70 tf_->transformPointCloud(fixed_frame_id, scan_in, cloud_out) ;
82 int main(
int argc,
char **argv)
84 ros::init(argc, argv,
"point_cloud_assembler");
86 ROS_WARN(
"The point_cloud_assembler_srv is deprecated. Please switch to " 87 "using the laser_scan_assembler. Documentation is available at " 88 "http://www.ros.org/wiki/laser_assembler");
90 pc_assembler.
start() ;
Maintains a history of incremental point clouds (usually from laser scans) and generates a point clou...
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)
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
~PointCloudAssemblerSrv()
void ConvertToCloud(const string &fixed_frame_id, const sensor_msgs::PointCloud &scan_in, sensor_msgs::PointCloud &cloud_out)
unsigned int GetPointsInScan(const sensor_msgs::PointCloud &scan)
Returns the number of points in the current scan.
void start()
Tells the assembler to start listening to input data It is possible that a derived class needs to ini...