Class ThreadSafeSynchronization

Inheritance Relationships

Base Type

Class Documentation

class ThreadSafeSynchronization : public rclcpp::wait_set_policies::detail::SynchronizationPolicyCommon

WaitSet policy that provides thread-safe synchronization for the wait set.

This class uses a “write-preferring RW lock” so that adding items to, and removing items from, the wait set will take priority over reading, i.e. waiting. This is done since add and remove calls will interrupt the wait set anyways so it is wasteful to do “fair” locking when there are many add/remove operations queued up.

There are some things to consider about the thread-safety provided by this policy. There are two categories of activities, reading and writing activities. The writing activities include all of the add and remove methods, as well as the prune_deleted_entities() method. The reading methods include the wait() method and keeping a WaitResult in scope. The reading and writing activities will not be run at the same time, and one will block the other. Therefore, if you are holding a WaitResult in scope, and try to add or remove an entity at the same time, they will block each other. The write activities will try to interrupt the wait() method by triggering a guard condition, but they have no way of causing the WaitResult to release its lock.

Protected Functions

inline explicit ThreadSafeSynchronization(rclcpp::Context::SharedPtr context)
~ThreadSafeSynchronization() = default
inline const std::array<std::shared_ptr<rclcpp::GuardCondition>, 1> &get_extra_guard_conditions()

Return any “extra” guard conditions needed to implement the synchronization policy.

This policy has one guard condition which is used to interrupt the wait set when adding and removing entities.

inline void interrupt_waiting_wait_set()

Interrupt any waiting wait set.

Used to interrupt the wait set when adding or removing items.

inline void sync_add_subscription(std::shared_ptr<rclcpp::SubscriptionBase> &&subscription, const rclcpp::SubscriptionWaitSetMask &mask, std::function<void(std::shared_ptr<rclcpp::SubscriptionBase>&&, const rclcpp::SubscriptionWaitSetMask&)> add_subscription_function)

Add subscription.

inline void sync_remove_subscription(std::shared_ptr<rclcpp::SubscriptionBase> &&subscription, const rclcpp::SubscriptionWaitSetMask &mask, std::function<void(std::shared_ptr<rclcpp::SubscriptionBase>&&, const rclcpp::SubscriptionWaitSetMask&)> remove_subscription_function)

Remove guard condition.

inline void sync_add_guard_condition(std::shared_ptr<rclcpp::GuardCondition> &&guard_condition, std::function<void(std::shared_ptr<rclcpp::GuardCondition>&&)> add_guard_condition_function)

Add guard condition.

inline void sync_remove_guard_condition(std::shared_ptr<rclcpp::GuardCondition> &&guard_condition, std::function<void(std::shared_ptr<rclcpp::GuardCondition>&&)> remove_guard_condition_function)

Remove guard condition.

inline void sync_add_timer(std::shared_ptr<rclcpp::TimerBase> &&timer, std::function<void(std::shared_ptr<rclcpp::TimerBase>&&)> add_timer_function)

Add timer.

inline void sync_remove_timer(std::shared_ptr<rclcpp::TimerBase> &&timer, std::function<void(std::shared_ptr<rclcpp::TimerBase>&&)> remove_timer_function)

Remove timer.

inline void sync_add_client(std::shared_ptr<rclcpp::ClientBase> &&client, std::function<void(std::shared_ptr<rclcpp::ClientBase>&&)> add_client_function)

Add client.

inline void sync_remove_client(std::shared_ptr<rclcpp::ClientBase> &&client, std::function<void(std::shared_ptr<rclcpp::ClientBase>&&)> remove_client_function)

Remove client.

inline void sync_add_service(std::shared_ptr<rclcpp::ServiceBase> &&service, std::function<void(std::shared_ptr<rclcpp::ServiceBase>&&)> add_service_function)

Add service.

inline void sync_remove_service(std::shared_ptr<rclcpp::ServiceBase> &&service, std::function<void(std::shared_ptr<rclcpp::ServiceBase>&&)> remove_service_function)

Remove service.

inline void sync_add_waitable(std::shared_ptr<rclcpp::Waitable> &&waitable, std::shared_ptr<void> &&associated_entity, std::function<void(std::shared_ptr<rclcpp::Waitable>&&, std::shared_ptr<void>&&)> add_waitable_function)

Add waitable.

inline void sync_remove_waitable(std::shared_ptr<rclcpp::Waitable> &&waitable, std::function<void(std::shared_ptr<rclcpp::Waitable>&&)> remove_waitable_function)

Remove waitable.

inline void sync_prune_deleted_entities(std::function<void()> prune_deleted_entities_function)

Prune deleted entities.

template<class WaitResultT>
inline WaitResultT sync_wait(std::chrono::nanoseconds time_to_wait_ns, std::function<void()> rebuild_rcl_wait_set, std::function<rcl_wait_set_t&()> get_rcl_wait_set, std::function<WaitResultT(WaitResultKind wait_result_kind)> create_wait_result)

Implements wait.

inline void sync_wait_result_acquire()
inline void sync_wait_result_release()

Protected Attributes

std::array<std::shared_ptr<rclcpp::GuardCondition>, 1> extra_guard_conditions_
rclcpp::wait_set_policies::detail::WritePreferringReadWriteLock wprw_lock_