Class CameraPublisher
- Defined in File camera_publisher.hpp 
Class Documentation
- 
class CameraPublisher
- Manages advertisements for publishing camera images. - CameraPublisher is a convenience class for publishing synchronized image and camera info topics using the standard topic naming convention, where the info topic name is “camera_info” in the same namespace as the base image topic. - On the client side, CameraSubscriber simplifies subscribing to camera images. - A CameraPublisher should always be created through a call to ImageTransport::advertiseCamera(), or copied from one that was. Once all copies of a specific CameraPublisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all CameraPublisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised. - Public Functions - 
IMAGE_TRANSPORT_PUBLIC CameraPublisher() = default
 - 
IMAGE_TRANSPORT_PUBLIC CameraPublisher(rclcpp::Node *node, const std::string &base_topic, rmw_qos_profile_t custom_qos = rmw_qos_profile_default, rclcpp::PublisherOptions = rclcpp::PublisherOptions())
 - 
IMAGE_TRANSPORT_PUBLIC CameraPublisher(RequiredInterfaces node_interfaces, const std::string &base_topic, rclcpp::QoS custom_qos, rclcpp::PublisherOptions = rclcpp::PublisherOptions())
 - IMAGE_TRANSPORT_PUBLIC size_t getNumSubscribers () const
- Returns the number of subscribers that are currently connected to this CameraPublisher. - Returns max(image topic subscribers, info topic subscribers). 
 - IMAGE_TRANSPORT_PUBLIC std::string getTopic () const
- Returns the base (image) topic of this CameraPublisher. 
 - IMAGE_TRANSPORT_PUBLIC std::string getInfoTopic () const
- Returns the camera info topic of this CameraPublisher. 
 - IMAGE_TRANSPORT_PUBLIC void publish (const sensor_msgs::msg::Image &image, const sensor_msgs::msg::CameraInfo &info) const
- Publish an (image, info) pair on the topics associated with this CameraPublisher. 
 - IMAGE_TRANSPORT_PUBLIC void publish (const sensor_msgs::msg::Image::ConstSharedPtr &image, const sensor_msgs::msg::CameraInfo::ConstSharedPtr &info) const
- Publish an (image, info) pair on the topics associated with this CameraPublisher. 
 - IMAGE_TRANSPORT_PUBLIC void publish (sensor_msgs::msg::Image::UniquePtr image, sensor_msgs::msg::CameraInfo::UniquePtr info) const
- Publish an (image, info) pair on the topics associated with this CameraPublisher. 
 - IMAGE_TRANSPORT_PUBLIC void publish (sensor_msgs::msg::Image &image, sensor_msgs::msg::CameraInfo &info, rclcpp::Time stamp) const
- Publish an (image, info) pair with given timestamp on the topics associated with this CameraPublisher. - Convenience version, which sets the timestamps of both image and info to stamp before publishing. 
 - IMAGE_TRANSPORT_PUBLIC void publish (sensor_msgs::msg::Image::UniquePtr image, sensor_msgs::msg::CameraInfo::UniquePtr info, rclcpp::Time stamp) const
- Publish an (image, info) pair with given timestamp on the topics associated with this CameraPublisher. - Convenience version, which sets the timestamps of both image and info to stamp before publishing. 
 - IMAGE_TRANSPORT_PUBLIC void shutdown ()
- Shutdown the advertisements associated with this Publisher. 
 - 
IMAGE_TRANSPORT_PUBLIC operator void*() const
 - inline IMAGE_TRANSPORT_PUBLIC bool operator< (const CameraPublisher &rhs) const
 - inline IMAGE_TRANSPORT_PUBLIC bool operator!= (const CameraPublisher &rhs) const
 - inline IMAGE_TRANSPORT_PUBLIC bool operator== (const CameraPublisher &rhs) const
 
- 
IMAGE_TRANSPORT_PUBLIC CameraPublisher() = default