#include <laserscan_to_pointcloud.h>
Public Member Functions | |
| ScanToPointCloud (ros::NodeHandle nh) | |
| Construct a new Scan To Point Cloud object. More... | |
Private Types | |
| typedef pcl::PointCloud< pcl::PointXYZ > | PointCloudXYZ |
Private Member Functions | |
| void | filenameCb (const std_msgs::String::ConstPtr &msg) |
| Callback for read file name in which store point cloud scanned. More... | |
| 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/pointclouds. More... | |
| void | scanCb (const sensor_msgs::LaserScan::ConstPtr &scan) |
| Callback for adding the new scan to the point cloud. More... | |
Private Attributes | |
| int | counter_ |
| Count number of scans finished to append on file name. More... | |
| std::string | file_name_ |
| File name to store point cloud scanned. More... | |
| ros::Subscriber | filename_sub_ |
| Subscriber to receive file name. More... | |
| bool | init_cloud_ = true |
| Attaches header info and more to total_cloud_ in the first iteration. More... | |
| ros::NodeHandle | nh_ |
| Pointer to the ROS node. More... | |
| laser_geometry::LaserProjection | projector_ |
| Instance of object LaserProjection to transform the laser scan into a point cloud. More... | |
| ros::Publisher | pub_ |
| Publisher for the point cloud. More... | |
| ros::ServiceServer | store_sub_ |
| Service for saving the point cloud. More... | |
| ros::Subscriber | sub_ |
| Subscriber for the laser scan. More... | |
| tf::TransformListener | tf_listener_ |
| Reference system of the listener. More... | |
| PointCloudXYZ::Ptr | total_cloud_ |
| Point cloud generated by the Leica. More... | |
Definition at line 29 of file laserscan_to_pointcloud.h.
|
private |
Definition at line 31 of file laserscan_to_pointcloud.h.
| ScanToPointCloud::ScanToPointCloud | ( | ros::NodeHandle | nh | ) |
Construct a new Scan To Point Cloud object.
Definition at line 24 of file laserscan_to_pointcloud.cpp.
|
private |
Callback for read file name in which store point cloud scanned.
| msg |
Definition at line 43 of file laserscan_to_pointcloud.cpp.
|
private |
Saves the cloud as .pcd format. The destination folder will be on package leica_scanstation_utils/pointclouds.
| req | Not used |
| res | Not used |
Definition at line 49 of file laserscan_to_pointcloud.cpp.
|
private |
Callback for adding the new scan to the point cloud.
| scan | New laser scan |
Definition at line 64 of file laserscan_to_pointcloud.cpp.
|
private |
Count number of scans finished to append on file name.
Definition at line 69 of file laserscan_to_pointcloud.h.
|
private |
File name to store point cloud scanned.
Definition at line 75 of file laserscan_to_pointcloud.h.
|
private |
Subscriber to receive file name.
Definition at line 123 of file laserscan_to_pointcloud.h.
|
private |
Attaches header info and more to total_cloud_ in the first iteration.
Definition at line 99 of file laserscan_to_pointcloud.h.
|
private |
Pointer to the ROS node.
Definition at line 105 of file laserscan_to_pointcloud.h.
|
private |
Instance of object LaserProjection to transform the laser scan into a point cloud.
Definition at line 81 of file laserscan_to_pointcloud.h.
|
private |
Publisher for the point cloud.
Definition at line 111 of file laserscan_to_pointcloud.h.
|
private |
Service for saving the point cloud.
Definition at line 129 of file laserscan_to_pointcloud.h.
|
private |
Subscriber for the laser scan.
Definition at line 117 of file laserscan_to_pointcloud.h.
|
private |
Reference system of the listener.
Definition at line 87 of file laserscan_to_pointcloud.h.
|
private |
Point cloud generated by the Leica.
Definition at line 93 of file laserscan_to_pointcloud.h.