Class ImageTransport
Defined in File image_transport.hpp
Class Documentation
-
class ImageTransport
Advertise and subscribe to image topics.
ImageTransport is analogous to ros::NodeHandle in that it contains advertise() and subscribe() functions for creating advertisements and subscriptions of image topics.
Public Types
-
using VoidPtr = std::shared_ptr<void>
-
using ImageConstPtr = sensor_msgs::msg::Image::ConstSharedPtr
-
using CameraInfoConstPtr = sensor_msgs::msg::CameraInfo::ConstSharedPtr
Public Functions
-
IMAGE_TRANSPORT_PUBLIC ~ImageTransport()
- IMAGE_TRANSPORT_PUBLIC Publisher advertise (const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
- IMAGE_TRANSPORT_PUBLIC Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, const Subscriber::Callback &callback, const VoidPtr &tracked_object=VoidPtr(), const TransportHints *transport_hints=nullptr)
Advertise an image topic with subcriber status callbacks.
Subscribe to an image topic, version for arbitrary std::function object.
- IMAGE_TRANSPORT_PUBLIC Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, const Subscriber::Callback &callback, const VoidPtr &tracked_object, const TransportHints *transport_hints, const rclcpp::SubscriptionOptions options)
Subscribe to an image topic, version for arbitrary std::function object.
- inline IMAGE_TRANSPORT_PUBLIC Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(*fp)(const ImageConstPtr &), const TransportHints *transport_hints=nullptr)
Subscribe to an image topic, version for bare function.
- inline IMAGE_TRANSPORT_PUBLIC Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, void(*fp)(const ImageConstPtr &), const TransportHints *transport_hints, const rclcpp::SubscriptionOptions options)
Subscribe to an image topic, version for bare function.
-
template<class T>
inline Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void (T::* fp)(const ImageConstPtr&), T *obj, const TransportHints *transport_hints = nullptr) Subscribe to an image topic, version for class member function with bare pointer.
-
template<class T>
inline Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void (T::* fp)(const ImageConstPtr&), T *obj, const TransportHints *transport_hints, const rclcpp::SubscriptionOptions options) Subscribe to an image topic, version for class member function with bare pointer.
Subscribe to an image topic, version for class member function with shared_ptr.
Subscribe to an image topic, version for class member function with shared_ptr.
- IMAGE_TRANSPORT_PUBLIC CameraPublisher advertiseCamera (const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise a synchronized camera raw image + info topic pair, simple version.
- IMAGE_TRANSPORT_PUBLIC CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const VoidPtr &tracked_object=VoidPtr(), const TransportHints *transport_hints=nullptr)
Advertise a synchronized camera raw image + info topic pair with subscriber status callbacks.
Subscribe to a synchronized image & camera info topic pair, version for arbitrary std::function object.
This version assumes the standard topic naming scheme, where the info topic is named “camera_info” in the same namespace as the base image topic.
- inline IMAGE_TRANSPORT_PUBLIC CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, void(*fp)(const ImageConstPtr &, const CameraInfoConstPtr &), const TransportHints *transport_hints=nullptr)
Subscribe to a synchronized image & camera info topic pair, version for bare function.
-
template<class T>
inline CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void (T::* fp)(const ImageConstPtr&, const CameraInfoConstPtr&), T *obj, const TransportHints *transport_hints = nullptr) Subscribe to a synchronized image & camera info topic pair, version for class member function with bare pointer.
Subscribe to a synchronized image & camera info topic pair, version for class member function with shared_ptr.
- IMAGE_TRANSPORT_PUBLIC std::vector< std::string > getDeclaredTransports () const
Returns the names of all transports declared in the system. Declared transports are not necessarily built or loadable.
- IMAGE_TRANSPORT_PUBLIC std::vector< std::string > getLoadableTransports () const
Returns the names of all transports that are loadable in the system.
-
using VoidPtr = std::shared_ptr<void>