Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
ScanToPointCloud Class Reference

#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...
 

Detailed Description

Definition at line 29 of file laserscan_to_pointcloud.h.

Member Typedef Documentation

typedef pcl::PointCloud<pcl::PointXYZ> ScanToPointCloud::PointCloudXYZ
private

Definition at line 31 of file laserscan_to_pointcloud.h.

Constructor & Destructor Documentation

ScanToPointCloud::ScanToPointCloud ( ros::NodeHandle  nh)

Construct a new Scan To Point Cloud object.

Definition at line 24 of file laserscan_to_pointcloud.cpp.

Member Function Documentation

void ScanToPointCloud::filenameCb ( const std_msgs::String::ConstPtr &  msg)
private

Callback for read file name in which store point cloud scanned.

Parameters
msg

Definition at line 43 of file laserscan_to_pointcloud.cpp.

bool ScanToPointCloud::saveCloudCb ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Saves the cloud as .pcd format. The destination folder will be on package leica_scanstation_utils/pointclouds.

Parameters
reqNot used
resNot used
Returns
true Default value
false Not used

Definition at line 49 of file laserscan_to_pointcloud.cpp.

void ScanToPointCloud::scanCb ( const sensor_msgs::LaserScan::ConstPtr &  scan)
private

Callback for adding the new scan to the point cloud.

Parameters
scanNew laser scan

Definition at line 64 of file laserscan_to_pointcloud.cpp.

Member Data Documentation

int ScanToPointCloud::counter_
private

Count number of scans finished to append on file name.

Definition at line 69 of file laserscan_to_pointcloud.h.

std::string ScanToPointCloud::file_name_
private

File name to store point cloud scanned.

Definition at line 75 of file laserscan_to_pointcloud.h.

ros::Subscriber ScanToPointCloud::filename_sub_
private

Subscriber to receive file name.

Definition at line 123 of file laserscan_to_pointcloud.h.

bool ScanToPointCloud::init_cloud_ = true
private

Attaches header info and more to total_cloud_ in the first iteration.

Definition at line 99 of file laserscan_to_pointcloud.h.

ros::NodeHandle ScanToPointCloud::nh_
private

Pointer to the ROS node.

Definition at line 105 of file laserscan_to_pointcloud.h.

laser_geometry::LaserProjection ScanToPointCloud::projector_
private

Instance of object LaserProjection to transform the laser scan into a point cloud.

Definition at line 81 of file laserscan_to_pointcloud.h.

ros::Publisher ScanToPointCloud::pub_
private

Publisher for the point cloud.

Definition at line 111 of file laserscan_to_pointcloud.h.

ros::ServiceServer ScanToPointCloud::store_sub_
private

Service for saving the point cloud.

Definition at line 129 of file laserscan_to_pointcloud.h.

ros::Subscriber ScanToPointCloud::sub_
private

Subscriber for the laser scan.

Definition at line 117 of file laserscan_to_pointcloud.h.

tf::TransformListener ScanToPointCloud::tf_listener_
private

Reference system of the listener.

Definition at line 87 of file laserscan_to_pointcloud.h.

PointCloudXYZ::Ptr ScanToPointCloud::total_cloud_
private

Point cloud generated by the Leica.

Definition at line 93 of file laserscan_to_pointcloud.h.


The documentation for this class was generated from the following files:


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