PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
SharedSubscription< RosMessageType > Class Template Reference

Shared class for a ROS subscription. More...

#include <px4_ros2/components/shared_subscription.hpp>

Inheritance diagram for SharedSubscription< RosMessageType >:

Public Types

using OnUpdateCallback = std::function< void(const typename RosMessageType::UniquePtr &)>
 

Public Member Functions

SharedSubscriptionCallbackInstance registerOnUpdateCallback (OnUpdateCallback callback)
 
const rclcpp::Subscription< RosMessageType >::SharedPtr & getSubscription () const
 

Static Public Member Functions

static SharedSubscriptioninstance (rclcpp::Node &node, const std::string &topic_name)
 
static SharedSubscriptionCallbackInstance create (rclcpp::Node &node, const std::string &topic_name, OnUpdateCallback callback)
 

Detailed Description

template<typename RosMessageType>
class SharedSubscription< RosMessageType >

Shared class for a ROS subscription.

Can be used for consistent callback ordering, by sharing a subscription instance, and to reduce resource (CPU load) overhead from creating multiple subscriptions in different components.

When using multiple nodes, a subscription per node is created.

Assumes the use of a single-threaded executor.


The documentation for this class was generated from the following file: