Go to the documentation of this file.
38 #ifndef PCL_ROS_IO_PCD_IO_H_
39 #define PCL_ROS_IO_PCD_IO_H_
41 #include <pcl/io/pcd_io.h>
95 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
128 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
132 #endif //#ifndef PCL_ROS_IO_PCD_IO_H_
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
PointCloud2::ConstPtr PointCloud2ConstPtr
std::string file_name_
The name of the file that contains the PointCloud data.
ros::Subscriber sub_input_
The input PointCloud subscriber.
sensor_msgs::PointCloud2 PointCloud2
sensor_msgs::PointCloud2 PointCloud2
void setPublishRate(double publish_rate)
Set the publishing rate in seconds.
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
pcl_ros::PCDWriter PCDWriter
Point Cloud Data (PCD) file format reader.
PointCloud2::Ptr PointCloud2Ptr
PointCloud2::ConstPtr PointCloud2ConstPtr
PointCloud2Ptr output_
The output point cloud dataset containing the points loaded from the file.
double getPublishRate()
Get the publishing rate in seconds.
pcl::PCDWriter impl_
The PCL implementation used.
PointCloud2::Ptr PointCloud2Ptr
pcl::PCDReader impl_
The PCL implementation used.
std::string getTFframe()
Get the TF frame the PointCloud is published in.
PCDReader()
Empty constructor.
std::string file_name_
The name of the file that contains the PointCloud data.
bool binary_mode_
Set to true if the output files should be saved in binary mode (true).
Point Cloud Data (PCD) file format writer.
pcl_ros::PCDReader PCDReader
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
void input_callback(const PointCloud2ConstPtr &cloud)
void setTFframe(std::string tf_frame)
Set the TF frame the PointCloud will be published in.
std::string tf_frame_
The TF frame the data should be published in ("/base_link" by default).
double publish_rate_
The publishing interval in seconds. Set to 0 to only publish once (default).
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40