Class SequentialSynchronization

Inheritance Relationships

Base Type

Class Documentation

class SequentialSynchronization : public rclcpp::wait_set_policies::detail::SynchronizationPolicyCommon

WaitSet policy that explicitly provides no thread synchronization.

Protected Functions

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

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

Since this policy provides no thread-safety, it also needs no extra guard conditions to implement it.

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 without thread-safety.

Does not throw, but storage function may throw.

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 without thread-safety.

Does not throw, but storage function may throw.

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 without thread-safety.

Does not throw, but storage function may throw.

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 without thread-safety.

Does not throw, but storage function may throw.

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

Add timer without thread-safety.

Does not throw, but storage function may throw.

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

Remove timer without thread-safety.

Does not throw, but storage function may throw.

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

Add client without thread-safety.

Does not throw, but storage function may throw.

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

Remove client without thread-safety.

Does not throw, but storage function may throw.

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

Add service without thread-safety.

Does not throw, but storage function may throw.

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

Remove service without thread-safety.

Does not throw, but storage function may throw.

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 without thread-safety.

Does not throw, but storage function may throw.

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

Remove waitable without thread-safety.

Does not throw, but storage function may throw.

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

Prune deleted entities without thread-safety.

Does not throw, but storage function may throw.

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 without any thread-safety.

inline void sync_wait_result_acquire()
inline void sync_wait_result_release()