Subscribe to ROS camera topics as data provider. More...
#include <camera_subscriber.h>
Public Member Functions | |
CameraSubscriber () noexcept | |
Constructs an empty subscriber. More... | |
CameraSubscriber (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept | |
Constructor that subscribes to the given ROS camera base topic. More... | |
void | set_subscribe_options (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept |
Configure ROS topic that is to be subscribed. More... | |
void | subscribe (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept |
Convenience function to subscribe to a ROS topic. More... | |
virtual std::string | topic () const noexcept override |
Return the configured ROS topic. More... | |
Protected Member Functions | |
virtual bool | is_configured () const noexcept override |
Check if the ROS subscriber is properly configured. More... | |
virtual void | subscribe_impl () noexcept override |
Create a ROS subscriber. More... | |
virtual void | unsubscribe_impl () noexcept override |
Shut the ROS subscriber down. More... | |
Private Member Functions | |
void | cb (const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) |
Private Attributes | |
std::string | base_topic_ |
image_transport::TransportHints | hints_ |
std::shared_ptr< image_transport::ImageTransport > | it_ |
uint32_t | queue_size_ |
image_transport::CameraSubscriber | sub_ |
Additional Inherited Members |
Subscribe to ROS camera topics as data provider.
This is a specialized subscriber that uses image_transport to subscribe to ROS camera topics. All messages which are received on the subscribed topics will be passed to the connected sinks for further processing.
Unlike regular ROS subscribers, this class can be associated with a publisher instance. In that case, the subscriber will delay subscription until the publisher is actively used and will unsubscribe (and stop passing data) as soon as the publisher becomes idle. This is a convenient method to save processing power if the filter pipeline is used only intermittently.
Definition at line 44 of file camera_subscriber.h.
|
inlinenoexcept |
Constructs an empty subscriber.
You need to call set_subscribe_options() and either subscribe() or subscribe_on_demand() to actually subscribe to a ROS topic.
Definition at line 51 of file camera_subscriber.h.
|
noexcept |
Constructor that subscribes to the given ROS camera base topic.
This constructor calls set_subscribe_options() and subscribe() for you.
it
ROS image_transport instance to handle the subscription base_topic
name of the ROS camera base topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
transport hints for the ROS image_transport frameworkDefinition at line 26 of file camera_subscriber.cpp.
|
private |
Definition at line 76 of file camera_subscriber.cpp.
|
overrideprotectedvirtualnoexcept |
Check if the ROS subscriber is properly configured.
Implements fkie_message_filters::SubscriberBase.
Definition at line 51 of file camera_subscriber.cpp.
|
noexcept |
Configure ROS topic that is to be subscribed.
All arguments are passed to the ROS client library; see the ROS documentation for further information. Calling this method will automatically unsubscribe any previously subscribed ROS topic.
it
ROS image_transport instance to handle the subscription base_topic
name of the ROS camera base topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
transport hints for the ROS image_transport frameworkDefinition at line 32 of file camera_subscriber.cpp.
|
noexcept |
Convenience function to subscribe to a ROS topic.
This function is equivalent to calling set_subscribe_options() and then subscribe().
it
ROS image_transport instance to handle the subscription base_topic
name of the ROS camera base topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
transport hints for the ROS image_transport frameworkDefinition at line 40 of file camera_subscriber.cpp.
|
overrideprotectedvirtualnoexcept |
Create a ROS subscriber.
Implements fkie_message_filters::SubscriberBase.
Definition at line 56 of file camera_subscriber.cpp.
|
overridevirtualnoexcept |
Return the configured ROS topic.
Implements fkie_message_filters::SubscriberBase.
Definition at line 46 of file camera_subscriber.cpp.
|
overrideprotectedvirtualnoexcept |
Shut the ROS subscriber down.
Implements fkie_message_filters::SubscriberBase.
Definition at line 71 of file camera_subscriber.cpp.
|
private |
Definition at line 117 of file camera_subscriber.h.
|
private |
Definition at line 119 of file camera_subscriber.h.
|
private |
Definition at line 116 of file camera_subscriber.h.
|
private |
Definition at line 118 of file camera_subscriber.h.
|
private |
Definition at line 120 of file camera_subscriber.h.