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... | |
virtual void | subscribe () |
Subscribe to the configured ROS topic. 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 void | subscribe_on_demand (PublisherBase &pub) |
Subscribe to the configured ROS topic whenever the given publisher is active. More... | |
virtual std::string | topic () const noexcept override |
Return the configured ROS topic. More... | |
virtual void | unsubscribe () |
Unsubscribe from 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 62 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 87 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 framework\nothrow
Definition at line 44 of file camera_subscriber.cpp.
|
private |
Definition at line 94 of file camera_subscriber.cpp.
|
overrideprotectedvirtualnoexcept |
Check if the ROS subscriber is properly configured.
\nothrow
Implements fkie_message_filters::SubscriberBase.
Definition at line 69 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 framework\nothrow
Definition at line 50 of file camera_subscriber.cpp.
void fkie_message_filters::SubscriberBase::subscribe |
Subscribe to the configured ROS topic.
This method does nothing if no ROS topic was configured or if the subscriber is subscribed already. Cancels the effect of subscribe_on_demand(), i.e. the subscriber will remain subscribed permanently.
\implthrow
Definition at line 64 of file publisher_subscriber_base.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 framework\nothrow
Definition at line 58 of file camera_subscriber.cpp.
|
overrideprotectedvirtualnoexcept |
Create a ROS subscriber.
\nothrow
Implements fkie_message_filters::SubscriberBase.
Definition at line 74 of file camera_subscriber.cpp.
void fkie_message_filters::SubscriberBase::subscribe_on_demand |
Subscribe to the configured ROS topic whenever the given publisher is active.
This method does nothing if no ROS topic was configured. Otherwise, it will immediately subscribe or unsubscribe depending on the publisher's current state. If the publisher becomes active or inactive, the subscriber's state will update accordingly.
pub
publisher\implthrow
Definition at line 76 of file publisher_subscriber_base.cpp.
|
overridevirtualnoexcept |
Return the configured ROS topic.
\nothrow
Implements fkie_message_filters::SubscriberBase.
Definition at line 64 of file camera_subscriber.cpp.
void fkie_message_filters::SubscriberBase::unsubscribe |
Unsubscribe from the configured ROS topic.
You can call subscribe() afterwards to re-subscribe to the ROS topic. This method does nothing if the subscriber is not subscribed to any ROS topic. Cancels the effect of subscribe_on_demand(), i.e. the subscriber will remain unsubscribed permanently.
\implthrow
Definition at line 70 of file publisher_subscriber_base.cpp.
|
overrideprotectedvirtualnoexcept |
Shut the ROS subscriber down.
\nothrow
Implements fkie_message_filters::SubscriberBase.
Definition at line 89 of file camera_subscriber.cpp.
|
private |
Definition at line 153 of file camera_subscriber.h.
|
private |
Definition at line 155 of file camera_subscriber.h.
|
private |
Definition at line 152 of file camera_subscriber.h.
|
private |
Definition at line 154 of file camera_subscriber.h.
|
private |
Definition at line 156 of file camera_subscriber.h.