Support for image_transport#

struct ImageTransportSubscription : public icey::Stream<sensor_msgs::msg::Image::ConstSharedPtr, image_transport::TransportLoadException, ImageTransportSubscriptionImpl>#

Public Types

using Base = Stream<sensor_msgs::msg::Image::ConstSharedPtr, image_transport::TransportLoadException, ImageTransportSubscriptionImpl>#

Public Functions

ImageTransportSubscription(Context &context, const std::string &base_topic_name, const std::string &transport, const rclcpp::QoS qos, const rclcpp::SubscriptionOptions &options = {})#
struct ImageTransportSubscriptionImpl#

Public Members

image_transport::Subscriber subscription#

The image_transport subs/pubs use PIMPL, so we can hold them by value.

struct ImageTransportPublisher : public icey::Stream<sensor_msgs::msg::Image::SharedPtr>#

Public Types

using Base = Stream<sensor_msgs::msg::Image::SharedPtr>#

Public Functions

ImageTransportPublisher(Context &context, const std::string &base_topic_name, const rclcpp::QoS qos, const rclcpp::PublisherOptions& = {})#
struct CameraSubscription : public icey::Stream<std::tuple<sensor_msgs::msg::Image::ConstSharedPtr, sensor_msgs::msg::CameraInfo::ConstSharedPtr>, image_transport::TransportLoadException, CameraSubscriptionImpl>#

Public Types

using Base = Stream<std::tuple<sensor_msgs::msg::Image::ConstSharedPtr, sensor_msgs::msg::CameraInfo::ConstSharedPtr>, image_transport::TransportLoadException, CameraSubscriptionImpl>#

Public Functions

CameraSubscription(Context &context, const std::string &base_topic_name, const std::string &transport, const rclcpp::QoS qos)#
struct CameraSubscriptionImpl#

Public Members

image_transport::CameraSubscriber subscription#

The image_transport sub/pub use PIMPL, so we can hold them by value.

struct CameraPublisher : public icey::Stream<std::tuple<sensor_msgs::msg::Image::SharedPtr, sensor_msgs::msg::CameraInfo::SharedPtr>>#

Public Types

using Base = Stream<std::tuple<sensor_msgs::msg::Image::SharedPtr, sensor_msgs::msg::CameraInfo::SharedPtr>>#

Public Functions

CameraPublisher(Context &context, const std::string &base_topic_name, const rclcpp::QoS qos)#