.. _program_listing_file_include_rclcpp_callback_group.hpp: Program Listing for File callback_group.hpp =========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/callback_group.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2014 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP__CALLBACK_GROUP_HPP_ #define RCLCPP__CALLBACK_GROUP_HPP_ #include #include #include #include #include #include "rclcpp/client.hpp" #include "rclcpp/context.hpp" #include "rclcpp/guard_condition.hpp" #include "rclcpp/publisher_base.hpp" #include "rclcpp/service.hpp" #include "rclcpp/subscription_base.hpp" #include "rclcpp/timer.hpp" #include "rclcpp/visibility_control.hpp" #include "rclcpp/waitable.hpp" namespace rclcpp { // Forward declarations for friend statement in class CallbackGroup namespace node_interfaces { class NodeServices; class NodeTimers; class NodeTopics; class NodeWaitables; } // namespace node_interfaces enum class CallbackGroupType { MutuallyExclusive, Reentrant }; class CallbackGroup { friend class rclcpp::node_interfaces::NodeServices; friend class rclcpp::node_interfaces::NodeTimers; friend class rclcpp::node_interfaces::NodeTopics; friend class rclcpp::node_interfaces::NodeWaitables; public: RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup) RCLCPP_PUBLIC explicit CallbackGroup( CallbackGroupType group_type, bool automatically_add_to_executor_with_node = true); RCLCPP_PUBLIC ~CallbackGroup(); template rclcpp::SubscriptionBase::SharedPtr find_subscription_ptrs_if(Function func) const { return _find_ptrs_if_impl(func, subscription_ptrs_); } template rclcpp::TimerBase::SharedPtr find_timer_ptrs_if(Function func) const { return _find_ptrs_if_impl(func, timer_ptrs_); } template rclcpp::ServiceBase::SharedPtr find_service_ptrs_if(Function func) const { return _find_ptrs_if_impl(func, service_ptrs_); } template rclcpp::ClientBase::SharedPtr find_client_ptrs_if(Function func) const { return _find_ptrs_if_impl(func, client_ptrs_); } template rclcpp::Waitable::SharedPtr find_waitable_ptrs_if(Function func) const { return _find_ptrs_if_impl(func, waitable_ptrs_); } RCLCPP_PUBLIC std::atomic_bool & can_be_taken_from(); RCLCPP_PUBLIC const CallbackGroupType & type() const; RCLCPP_PUBLIC void collect_all_ptrs( std::function sub_func, std::function service_func, std::function client_func, std::function timer_func, std::function waitable_func) const; RCLCPP_PUBLIC std::atomic_bool & get_associated_with_executor_atomic(); RCLCPP_PUBLIC bool automatically_add_to_executor_with_node() const; RCLCPP_PUBLIC rclcpp::GuardCondition::SharedPtr get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr); RCLCPP_PUBLIC void trigger_notify_guard_condition(); protected: RCLCPP_DISABLE_COPY(CallbackGroup) RCLCPP_PUBLIC void add_publisher(const rclcpp::PublisherBase::SharedPtr publisher_ptr); RCLCPP_PUBLIC void add_subscription(const rclcpp::SubscriptionBase::SharedPtr subscription_ptr); RCLCPP_PUBLIC void add_timer(const rclcpp::TimerBase::SharedPtr timer_ptr); RCLCPP_PUBLIC void add_service(const rclcpp::ServiceBase::SharedPtr service_ptr); RCLCPP_PUBLIC void add_client(const rclcpp::ClientBase::SharedPtr client_ptr); RCLCPP_PUBLIC void add_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr); RCLCPP_PUBLIC void remove_waitable(const rclcpp::Waitable::SharedPtr waitable_ptr) noexcept; CallbackGroupType type_; // Mutex to protect the subsequent vectors of pointers. mutable std::mutex mutex_; std::atomic_bool associated_with_executor_; std::vector subscription_ptrs_; std::vector timer_ptrs_; std::vector service_ptrs_; std::vector client_ptrs_; std::vector waitable_ptrs_; std::atomic_bool can_be_taken_from_; const bool automatically_add_to_executor_with_node_; // defer the creation of the guard condition std::shared_ptr notify_guard_condition_ = nullptr; std::recursive_mutex notify_guard_condition_mutex_; private: template typename TypeT::SharedPtr _find_ptrs_if_impl( Function func, const std::vector & vect_ptrs) const { std::lock_guard lock(mutex_); for (auto & weak_ptr : vect_ptrs) { auto ref_ptr = weak_ptr.lock(); if (ref_ptr && func(ref_ptr)) { return ref_ptr; } } return typename TypeT::SharedPtr(); } }; } // namespace rclcpp #endif // RCLCPP__CALLBACK_GROUP_HPP_