Public Member Functions | Private Types | Private Attributes | List of all members
point_cloud_transport::PointCloudTransport Class Reference

#include <point_cloud_transport.h>

Inheritance diagram for point_cloud_transport::PointCloudTransport:
Inheritance graph
[legend]

Public Member Functions

point_cloud_transport::Publisher advertise (const std::string &base_topic, uint32_t queue_size, bool latch=false)
 Advertise a PointCloud2 topic, simple version. More...
 
point_cloud_transport::Publisher advertise (const std::string &base_topic, uint32_t queue_size, const point_cloud_transport::SubscriberStatusCallback &connect_cb, const point_cloud_transport::SubscriberStatusCallback &disconnect_cb={}, const ros::VoidPtr &tracked_object={}, bool latch=false)
 Advertise an PointCloud2 topic with subscriber status callbacks. More...
 
 PointCloudTransport (const ros::NodeHandle &nh)
 Constructor. More...
 
point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::PointCloud2ConstPtr &)> &callback, const ros::VoidPtr &tracked_object={}, const point_cloud_transport::TransportHints &transport_hints={}, bool allow_concurrent_callbacks=false)
 Subscribe to a point cloud topic, version for arbitrary boost::function object. More...
 
point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::PointCloud2ConstPtr &), const point_cloud_transport::TransportHints &transport_hints={}, bool allow_concurrent_callbacks=false)
 Subscribe to a point cloud topic, version for bare function. More...
 
template<class T >
point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::PointCloud2ConstPtr &), const boost::shared_ptr< T > &obj, const point_cloud_transport::TransportHints &transport_hints={}, bool allow_concurrent_callbacks=false)
 Subscribe to a point cloud topic, version for class member function with shared_ptr. More...
 
template<class T >
point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::PointCloud2ConstPtr &), T *obj, const point_cloud_transport::TransportHints &transport_hints={}, bool allow_concurrent_callbacks=false)
 Subscribe to a point cloud topic, version for class member function with bare pointer. More...
 
- Public Member Functions inherited from point_cloud_transport::PointCloudTransportLoader
std::vector< std::string > getDeclaredTransports () const
 
std::unordered_map< std::string, std::string > getLoadableTransports () const
 Returns the names of all transports that are loadable in the system (keys are lookup names, values are names). More...
 
PubLoaderPtr getPublisherLoader () const
 The loader that can load publisher plugins. More...
 
SubLoaderPtr getSubscriberLoader () const
 The loader that can load subscriber plugins. More...
 
 PointCloudTransportLoader ()
 Constructor. More...
 
virtual ~PointCloudTransportLoader ()
 Destructor. More...
 

Private Types

typedef boost::shared_ptr< Impl > ImplPtr
 
typedef boost::weak_ptr< Impl > ImplWPtr
 

Private Attributes

ImplPtr impl_
 

Detailed Description

Advertise and subscribe to PointCloud2 topics.

PointCloudTransport is analogous to ros::NodeHandle in that it contains advertise() and subscribe() functions for creating advertisements and subscriptions of PointCloud2 topics.

Definition at line 108 of file point_cloud_transport.h.

Member Typedef Documentation

◆ ImplPtr

Definition at line 166 of file point_cloud_transport.h.

◆ ImplWPtr

typedef boost::weak_ptr<Impl> point_cloud_transport::PointCloudTransport::ImplWPtr
private

Definition at line 168 of file point_cloud_transport.h.

Constructor & Destructor Documentation

◆ PointCloudTransport()

point_cloud_transport::PointCloudTransport::PointCloudTransport ( const ros::NodeHandle nh)
explicit

Constructor.

Member Function Documentation

◆ advertise() [1/2]

point_cloud_transport::Publisher point_cloud_transport::PointCloudTransport::advertise ( const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)

Advertise a PointCloud2 topic, simple version.

◆ advertise() [2/2]

point_cloud_transport::Publisher point_cloud_transport::PointCloudTransport::advertise ( const std::string &  base_topic,
uint32_t  queue_size,
const point_cloud_transport::SubscriberStatusCallback connect_cb,
const point_cloud_transport::SubscriberStatusCallback disconnect_cb = {},
const ros::VoidPtr tracked_object = {},
bool  latch = false 
)

Advertise an PointCloud2 topic with subscriber status callbacks.

◆ subscribe() [1/4]

point_cloud_transport::Subscriber point_cloud_transport::PointCloudTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
const boost::function< void(const sensor_msgs::PointCloud2ConstPtr &)> &  callback,
const ros::VoidPtr tracked_object = {},
const point_cloud_transport::TransportHints transport_hints = {},
bool  allow_concurrent_callbacks = false 
)

Subscribe to a point cloud topic, version for arbitrary boost::function object.

◆ subscribe() [2/4]

point_cloud_transport::Subscriber point_cloud_transport::PointCloudTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
void(*)(const sensor_msgs::PointCloud2ConstPtr &)  fp,
const point_cloud_transport::TransportHints transport_hints = {},
bool  allow_concurrent_callbacks = false 
)
inline

Subscribe to a point cloud topic, version for bare function.

Definition at line 132 of file point_cloud_transport.h.

◆ subscribe() [3/4]

template<class T >
point_cloud_transport::Subscriber point_cloud_transport::PointCloudTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::PointCloud2ConstPtr &)  fp,
const boost::shared_ptr< T > &  obj,
const point_cloud_transport::TransportHints transport_hints = {},
bool  allow_concurrent_callbacks = false 
)
inline

Subscribe to a point cloud topic, version for class member function with shared_ptr.

Definition at line 155 of file point_cloud_transport.h.

◆ subscribe() [4/4]

template<class T >
point_cloud_transport::Subscriber point_cloud_transport::PointCloudTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::PointCloud2ConstPtr &)  fp,
T *  obj,
const point_cloud_transport::TransportHints transport_hints = {},
bool  allow_concurrent_callbacks = false 
)
inline

Subscribe to a point cloud topic, version for class member function with bare pointer.

Definition at line 144 of file point_cloud_transport.h.

Member Data Documentation

◆ impl_

ImplPtr point_cloud_transport::PointCloudTransport::impl_
private

Definition at line 170 of file point_cloud_transport.h.


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


point_cloud_transport
Author(s): Jakub Paplham
autogenerated on Sat Jun 17 2023 02:48:44