Class IntraProcessManager

Nested Relationships

Nested Types

Class Documentation

class IntraProcessManager

This class performs intra process communication between nodes.

This class is used in the creation of publishers and subscriptions. A singleton instance of this class is owned by a rclcpp::Context and a rclcpp::Node can use an associated Context to get an instance of this class. Nodes which do not have a common Context will not exchange intra process messages because they do not share access to the same instance of this class.

When a Node creates a subscription, it can also create a helper class, called SubscriptionIntraProcess, meant to receive intra process messages. It can be registered with this class. It is also allocated an id which is unique among all publishers and subscriptions in this process and that is associated to the subscription.

When a Node creates a publisher, as with subscriptions, a helper class can be registered with this class. This is required in order to publish intra-process messages. It is also allocated an id which is unique among all publishers and subscriptions in this process and that is associated to the publisher.

When a publisher or a subscription are registered, this class checks to see which other subscriptions or publishers it will communicate with, i.e. they have the same topic and compatible QoS.

When the user publishes a message, if intra-process communication is enabled on the publisher, the message is given to this class. Using the publisher id, a list of recipients for the message is selected. For each subscription in the list, this class stores the message, whether sharing ownership or making a copy, in a buffer associated with the subscription helper class.

The subscription helper class contains a buffer where published intra-process messages are stored until they are taken from the subscription. Depending on the data type stored in the buffer, the subscription helper class can request either shared or exclusive ownership on the message.

Thus, when an intra-process message is published, this class knows how many intra-process subscriptions needs it and how many require ownership. This information allows this class to operate efficiently by performing the fewest number of copies of the message required.

This class is neither CopyConstructable nor CopyAssignable.

Public Functions

IntraProcessManager()
virtual ~IntraProcessManager()
template<typename ROSMessageType, typename Alloc = std::allocator<ROSMessageType>>
inline uint64_t add_subscription(rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr subscription)

Register a subscription with the manager, returns subscriptions unique id.

This method stores the subscription intra process object, together with the information of its wrapped subscription (i.e. topic name and QoS).

In addition this generates a unique intra process id for the subscription.

Parameters:

subscription – the SubscriptionIntraProcess to register.

Returns:

an unsigned 64-bit integer which is the subscription’s unique id.

void remove_subscription(uint64_t intra_process_subscription_id)

Unregister a subscription using the subscription’s unique id.

This method does not allocate memory.

Parameters:

intra_process_subscription_id – id of the subscription to remove.

uint64_t add_publisher(rclcpp::PublisherBase::SharedPtr publisher, rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr buffer = rclcpp::experimental::buffers::IntraProcessBufferBase::SharedPtr())

Register a publisher with the manager, returns the publisher unique id.

This method stores the publisher intra process object, together with the information of its wrapped publisher (i.e. topic name and QoS).

If the publisher’s durability is transient local, its buffer pointer should be passed and the method will store it as well.

In addition this generates a unique intra process id for the publisher.

Parameters:
  • publisher – publisher to be registered with the manager.

  • buffer – publisher’s buffer to be stored if its duability is transient local.

Returns:

an unsigned 64-bit integer which is the publisher’s unique id.

void remove_publisher(uint64_t intra_process_publisher_id)

Unregister a publisher using the publisher’s unique id.

This method does not allocate memory.

Parameters:

intra_process_publisher_id – id of the publisher to remove.

template<typename MessageT, typename ROSMessageType, typename Alloc, typename Deleter = std::default_delete<MessageT>>
inline void do_intra_process_publish(uint64_t intra_process_publisher_id, std::unique_ptr<MessageT, Deleter> message, typename allocator::AllocRebind<MessageT, Alloc>::allocator_type &allocator)

Publishes an intra-process message, passed as a unique pointer.

This is one of the two methods for publishing intra-process.

Using the intra-process publisher id, a list of recipients is obtained. This list is split in half, depending whether they require ownership or not.

This particular method takes a unique pointer as input. The pointer can be promoted to a shared pointer and passed to all the subscriptions that do not require ownership. In case of subscriptions requiring ownership, the message will be copied for all of them except the last one, when ownership can be transferred.

This method can save an additional copy compared to the shared pointer one.

This method can throw an exception if the publisher id is not found or if the publisher shared_ptr given to add_publisher has gone out of scope.

This method does allocate memory.

Parameters:
  • intra_process_publisher_id – the id of the publisher of this message.

  • message – the message that is being stored.

  • allocator – for allocations when buffering messages.

template<typename MessageT, typename ROSMessageType, typename Alloc, typename Deleter = std::default_delete<MessageT>>
inline std::shared_ptr<const MessageT> do_intra_process_publish_and_return_shared(uint64_t intra_process_publisher_id, std::unique_ptr<MessageT, Deleter> message, typename allocator::AllocRebind<MessageT, Alloc>::allocator_type &allocator)
template<typename MessageT, typename Alloc, typename Deleter, typename ROSMessageType>
inline void add_shared_msg_to_buffer(std::shared_ptr<const MessageT> message, uint64_t subscription_id)
template<typename MessageT, typename Alloc, typename Deleter, typename ROSMessageType>
inline void add_owned_msg_to_buffer(std::unique_ptr<MessageT, Deleter> message, uint64_t subscription_id, typename allocator::AllocRebind<MessageT, Alloc>::allocator_type &allocator)
bool matches_any_publishers(const rmw_gid_t *id) const

Return true if the given rmw_gid_t matches any stored Publishers.

size_t get_subscription_count(uint64_t intra_process_publisher_id) const

Return the number of intraprocess subscriptions that are matched with a given publisher id.

rclcpp::experimental::SubscriptionIntraProcessBase::SharedPtr get_subscription_intra_process(uint64_t intra_process_subscription_id)
size_t lowest_available_capacity(const uint64_t intra_process_publisher_id) const

Return the lowest available capacity for all subscription buffers for a publisher id.