Class CameraSubscriber
Defined in File camera_subscriber.hpp
Class Documentation
-
class CameraSubscriber
Manages a subscription callback on synchronized Image and CameraInfo topics.
CameraSubscriber is the client-side counterpart to CameraPublisher, and assumes the same topic naming convention. The callback is of type:
void callback(const sensor_msgs::msg::Image::ConstSharedPtr&, const sensor_msgs::msg::CameraInfo::ConstSharedPtr&);
A CameraSubscriber should always be created through a call to ImageTransport::subscribeCamera(), or copied from one that was. Once all copies of a specific CameraSubscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all CameraSubscriber for a given topic go out of scope the topic will be unsubscribed.
Public Types
-
typedef std::function<void(const sensor_msgs::msg::Image::ConstSharedPtr&, const sensor_msgs::msg::CameraInfo::ConstSharedPtr&)> Callback
Public Functions
-
IMAGE_TRANSPORT_PUBLIC CameraSubscriber() = default
-
IMAGE_TRANSPORT_PUBLIC CameraSubscriber(rclcpp::Node *node, const std::string &base_topic, const Callback &callback, const std::string &transport, rmw_qos_profile_t = rmw_qos_profile_default)
- IMAGE_TRANSPORT_PUBLIC std::string getTopic () const
Get the base topic (on which the raw image is published).
- IMAGE_TRANSPORT_PUBLIC std::string getInfoTopic () const
Get the camera info topic.
- IMAGE_TRANSPORT_PUBLIC size_t getNumPublishers () const
Returns the number of publishers this subscriber is connected to.
- IMAGE_TRANSPORT_PUBLIC std::string getTransport () const
Returns the name of the transport being used.
- IMAGE_TRANSPORT_PUBLIC void shutdown ()
Unsubscribe the callback associated with this CameraSubscriber.
-
IMAGE_TRANSPORT_PUBLIC operator void*() const
- inline IMAGE_TRANSPORT_PUBLIC bool operator< (const CameraSubscriber &rhs) const
- inline IMAGE_TRANSPORT_PUBLIC bool operator!= (const CameraSubscriber &rhs) const
- inline IMAGE_TRANSPORT_PUBLIC bool operator== (const CameraSubscriber &rhs) const
-
typedef std::function<void(const sensor_msgs::msg::Image::ConstSharedPtr&, const sensor_msgs::msg::CameraInfo::ConstSharedPtr&)> Callback