Class PointCloudTransport
Defined in File point_cloud_transport.hpp
Inheritance Relationships
Base Type
public point_cloud_transport::PointCloudTransportLoader
(Class PointCloudTransportLoader)
Class Documentation
-
class PointCloudTransport : public point_cloud_transport::PointCloudTransportLoader
Public Functions
Constructor.
-
POINT_CLOUD_TRANSPORT_PUBLIC ~PointCloudTransport() override = default
- inline POINT_CLOUD_TRANSPORT_PUBLIC std::string getTransportOrDefault (const TransportHints *transport_hints)
- inline POINT_CLOUD_TRANSPORT_PUBLIC Publisher advertise (const std::string &base_topic, uint32_t queue_size)
Advertise a PointCloud2 topic, simple version.
- inline POINT_CLOUD_TRANSPORT_PUBLIC Publisher advertise (const std::string &base_topic, uint32_t queue_size, const rclcpp::PublisherOptions &options)
Advertise a PointCloud2 topic, simple version.
- inline POINT_CLOUD_TRANSPORT_PUBLIC Publisher advertise (const std::string &base_topic, rmw_qos_profile_t custom_qos, const rclcpp::PublisherOptions &options=rclcpp::PublisherOptions())
- inline POINT_CLOUD_TRANSPORT_PUBLIC point_cloud_transport::Subscriber subscribe (const std::string &base_topic, rmw_qos_profile_t custom_qos, const std::function< void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> &callback, const VoidPtr &tracked_object={}, const point_cloud_transport::TransportHints *transport_hints=nullptr)
Advertise an PointCloud2 topic with subscriber status callbacks.
Subscribe to a point cloud topic, version for arbitrary std::function object.
- inline POINT_CLOUD_TRANSPORT_PUBLIC point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, const std::function< void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &)> &callback, const VoidPtr &tracked_object={}, const point_cloud_transport::TransportHints *transport_hints=nullptr)
Subscribe to a point cloud topic, version for arbitrary std::function object.
- inline POINT_CLOUD_TRANSPORT_PUBLIC point_cloud_transport::Subscriber subscribe (const std::string &base_topic, rmw_qos_profile_t custom_qos, void(*fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &), const point_cloud_transport::TransportHints *transport_hints=nullptr)
Subscribe to a point cloud topic, version for bare function.
- inline POINT_CLOUD_TRANSPORT_PUBLIC point_cloud_transport::Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &), const point_cloud_transport::TransportHints *transport_hints=nullptr)
Subscribe to a point cloud topic, version for class member function with bare pointer.
Subscribe to a point cloud topic, version for class member function with shared_ptr.