Template Class SubscriptionIntraProcess

Inheritance Relationships

Base Type

Class Documentation

template<typename MessageT, typename SubscribedType, typename SubscribedTypeAlloc = std::allocator<SubscribedType>, typename SubscribedTypeDeleter = std::default_delete<SubscribedType>, typename ROSMessageType = SubscribedType, typename Alloc = std::allocator<void>>
class SubscriptionIntraProcess : public rclcpp::experimental::SubscriptionIntraProcessBuffer<SubscribedType, std::allocator<SubscribedType>, std::default_delete<SubscribedType>, SubscribedType>

Public Types

using MessageAllocTraits = typename SubscriptionIntraProcessBufferT::SubscribedTypeAllocatorTraits
using MessageAlloc = typename SubscriptionIntraProcessBufferT::SubscribedTypeAllocator
using ConstMessageSharedPtr = typename SubscriptionIntraProcessBufferT::ConstDataSharedPtr
using MessageUniquePtr = typename SubscriptionIntraProcessBufferT::SubscribedTypeUniquePtr
using BufferUniquePtr = typename SubscriptionIntraProcessBufferT::BufferUniquePtr

Public Functions

inline SubscriptionIntraProcess(AnySubscriptionCallback<MessageT, Alloc> callback, std::shared_ptr<Alloc> allocator, rclcpp::Context::SharedPtr context, const std::string &topic_name, const rclcpp::QoS &qos_profile, rclcpp::IntraProcessBufferType buffer_type)
virtual ~SubscriptionIntraProcess() = default
inline virtual std::shared_ptr<void> take_data() override

Take the data so that it can be consumed with execute.

NOTE: take_data is a partial fix to a larger design issue with the multithreaded executor. This method is likely to be removed when a more permanent fix is implemented. A longterm fix is currently being discussed here: https://github.com/ros2/rclcpp/pull/1276

This method takes the data from the underlying data structure and writes it to the void shared pointer data that is passed into the method. The data can then be executed with the execute method.

Before calling this method, the Waitable should be added to a wait set, waited on, and then updated.

Example usage:

// ... create a wait set and a Waitable
// Add the Waitable to the wait set
waitable.add_to_wait_set(wait_set);
// Wait
rcl_ret_t wait_ret = rcl_wait(wait_set);
// ... error handling
// Update the Waitable
waitable.update(wait_set);
// Execute any entities of the Waitable that may be ready
std::shared_ptr<void> data = waitable.take_data();
inline virtual void execute(std::shared_ptr<void> &data) override

Execute data that is passed in.

Before calling this method, the Waitable should be added to a wait set, waited on, and then updated - and the take_data method should be called.

Example usage:

// ... create a wait set and a Waitable
// Add the Waitable to the wait set
waitable.add_to_wait_set(wait_set);
// Wait
rcl_ret_t wait_ret = rcl_wait(wait_set);
// ... error handling
// Update the Waitable
waitable.update(wait_set);
// Execute any entities of the Waitable that may be ready
std::shared_ptr<void> data = waitable.take_data();
waitable.execute(data);

Protected Functions

template<typename T>
inline std::enable_if<std::is_same<T, rcl_serialized_message_t>::value, void>::type execute_impl(std::shared_ptr<void> &data)
template<class T>
inline std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type execute_impl(std::shared_ptr<void> &data)

Protected Attributes

AnySubscriptionCallback<MessageT, Alloc> any_callback_