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