19 #ifndef _LASERSCAN_TO_POINTCLOUD_H 20 #define _LASERSCAN_TO_POINTCLOUD_H 25 #include "pcl_conversions/pcl_conversions.h" 26 #include "std_srvs/Trigger.h" 27 #include "std_msgs/String.h" 46 void scanCb(
const sensor_msgs::LaserScan::ConstPtr& scan);
56 bool saveCloudCb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
63 void filenameCb(
const std_msgs::String::ConstPtr& msg);
PointCloudXYZ::Ptr total_cloud_
Point cloud generated by the Leica.
tf::TransformListener tf_listener_
Reference system of the listener.
ScanToPointCloud(ros::NodeHandle nh)
Construct a new Scan To Point Cloud object.
laser_geometry::LaserProjection projector_
Instance of object LaserProjection to transform the laser scan into a point cloud.
ros::Subscriber sub_
Subscriber for the laser scan.
bool init_cloud_
Attaches header info and more to total_cloud_ in the first iteration.
ros::Subscriber filename_sub_
Subscriber to receive file name.
ros::NodeHandle nh_
Pointer to the ROS node.
bool saveCloudCb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Saves the cloud as .pcd format. The destination folder will be on package leica_scanstation_utils/poi...
void scanCb(const sensor_msgs::LaserScan::ConstPtr &scan)
Callback for adding the new scan to the point cloud.
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
ros::Publisher pub_
Publisher for the point cloud.
std::string file_name_
File name to store point cloud scanned.
void filenameCb(const std_msgs::String::ConstPtr &msg)
Callback for read file name in which store point cloud scanned.
ros::ServiceServer store_sub_
Service for saving the point cloud.
int counter_
Count number of scans finished to append on file name.