laserscan_to_pointcloud.h
Go to the documentation of this file.
1 
18 #pragma once
19 #ifndef _LASERSCAN_TO_POINTCLOUD_H
20 #define _LASERSCAN_TO_POINTCLOUD_H
21 
22 #include "ros/ros.h"
23 #include <tf/transform_listener.h>
25 #include "pcl_conversions/pcl_conversions.h"
26 #include "std_srvs/Trigger.h"
27 #include "std_msgs/String.h"
28 
30 {
31  typedef pcl::PointCloud<pcl::PointXYZ> PointCloudXYZ;
32 
33 public:
39 
40 private:
46  void scanCb(const sensor_msgs::LaserScan::ConstPtr& scan);
47 
56  bool saveCloudCb(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
57 
63  void filenameCb(const std_msgs::String::ConstPtr& msg);
64 
69  int counter_;
70 
75  std::string file_name_;
76 
82 
88 
93  PointCloudXYZ::Ptr total_cloud_;
94 
99  bool init_cloud_ = true;
100 
106 
112 
118 
124 
130 };
131 
132 #endif
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.


leica_gazebo_simulation
Author(s): Ines Lara Sicilia
autogenerated on Mon Feb 22 2021 03:50:48