Public Types | Public Member Functions | Protected Attributes | Private Attributes | List of all members
pcl_ros::PCDReader Class Reference

Point Cloud Data (PCD) file format reader. More...

#include <pcd_io.h>

Inheritance diagram for pcl_ros::PCDReader:
Inheritance graph
[legend]

Public Types

typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud2::ConstPtr PointCloud2ConstPtr
 
typedef PointCloud2::Ptr PointCloud2Ptr
 
- Public Types inherited from pcl_ros::PCLNodelet
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef pcl_msgs::ModelCoefficients ModelCoefficients
 
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
 
typedef ModelCoefficients::Ptr ModelCoefficientsPtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 

Public Member Functions

double getPublishRate ()
 Get the publishing rate in seconds. More...
 
std::string getTFframe ()
 Get the TF frame the PointCloud is published in. More...
 
virtual void onInit ()
 Nodelet initialization routine. Reads in global parameters used by all nodelets. More...
 
 PCDReader ()
 Empty constructor. More...
 
void setPublishRate (double publish_rate)
 Set the publishing rate in seconds. More...
 
void setTFframe (std::string tf_frame)
 Set the TF frame the PointCloud will be published in. More...
 
- Public Member Functions inherited from pcl_ros::PCLNodelet
 PCLNodelet ()
 Empty constructor. More...
 
- Public Member Functions inherited from nodelet_topic_tools::NodeletLazy
 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Attributes

std::string file_name_
 The name of the file that contains the PointCloud data. More...
 
PointCloud2Ptr output_
 The output point cloud dataset containing the points loaded from the file. More...
 
double publish_rate_
 The publishing interval in seconds. Set to 0 to only publish once (default). More...
 
std::string tf_frame_
 The TF frame the data should be published in ("/base_link" by default). More...
 
- Protected Attributes inherited from pcl_ros::PCLNodelet
bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
bool latched_indices_
 Set to true if the indices topic is latched. More...
 
int max_queue_size_
 The maximum queue size (default: 3). More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
message_filters::Subscriber< PointIndicessub_indices_filter_
 The message filter subscriber for PointIndices. More...
 
message_filters::Subscriber< PointCloudsub_input_filter_
 The message filter subscriber for PointCloud2. More...
 
tf::TransformListener tf_listener_
 TF listener object. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

Private Attributes

pcl::PCDReader impl_
 The PCL implementation used. More...
 

Additional Inherited Members

- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointIndicesConstPtr &indices, const std::string &topic_name="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
bool isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
virtual void subscribe ()
 Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility. More...
 
virtual void unsubscribe ()
 
- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Point Cloud Data (PCD) file format reader.

Author
Radu Bogdan Rusu

Definition at line 50 of file pcd_io.h.

Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_ros::PCDReader::PointCloud2

Definition at line 53 of file pcd_io.h.

typedef PointCloud2::ConstPtr pcl_ros::PCDReader::PointCloud2ConstPtr

Definition at line 55 of file pcd_io.h.

typedef PointCloud2::Ptr pcl_ros::PCDReader::PointCloud2Ptr

Definition at line 54 of file pcd_io.h.

Constructor & Destructor Documentation

pcl_ros::PCDReader::PCDReader ( )
inline

Empty constructor.

Definition at line 58 of file pcd_io.h.

Member Function Documentation

double pcl_ros::PCDReader::getPublishRate ( )
inline

Get the publishing rate in seconds.

Definition at line 68 of file pcd_io.h.

std::string pcl_ros::PCDReader::getTFframe ( )
inline

Get the TF frame the PointCloud is published in.

Definition at line 76 of file pcd_io.h.

void pcl_ros::PCDReader::onInit ( )
virtual

Nodelet initialization routine. Reads in global parameters used by all nodelets.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 43 of file pcd_io.cpp.

void pcl_ros::PCDReader::setPublishRate ( double  publish_rate)
inline

Set the publishing rate in seconds.

Parameters
publish_ratethe publishing rate in seconds

Definition at line 65 of file pcd_io.h.

void pcl_ros::PCDReader::setTFframe ( std::string  tf_frame)
inline

Set the TF frame the PointCloud will be published in.

Parameters
tf_framethe TF frame the PointCloud will be published in

Definition at line 73 of file pcd_io.h.

Member Data Documentation

std::string pcl_ros::PCDReader::file_name_
protected

The name of the file that contains the PointCloud data.

Definition at line 86 of file pcd_io.h.

pcl::PCDReader pcl_ros::PCDReader::impl_
private

The PCL implementation used.

Definition at line 93 of file pcd_io.h.

PointCloud2Ptr pcl_ros::PCDReader::output_
protected

The output point cloud dataset containing the points loaded from the file.

Definition at line 89 of file pcd_io.h.

double pcl_ros::PCDReader::publish_rate_
protected

The publishing interval in seconds. Set to 0 to only publish once (default).

Definition at line 80 of file pcd_io.h.

std::string pcl_ros::PCDReader::tf_frame_
protected

The TF frame the data should be published in ("/base_link" by default).

Definition at line 83 of file pcd_io.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:19