.. _program_listing_file_include_rclcpp_executor.hpp: Program Listing for File executor.hpp ===================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/executor.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__EXECUTOR_HPP_ #define RCLCPP__EXECUTOR_HPP_ #include #include #include #include #include #include #include #include #include #include #include #include "rcl/guard_condition.h" #include "rcl/wait.h" #include "rclcpp/executors/executor_notify_waitable.hpp" #include "rcpputils/scope_exit.hpp" #include "rclcpp/context.hpp" #include "rclcpp/contexts/default_context.hpp" #include "rclcpp/guard_condition.hpp" #include "rclcpp/executor_options.hpp" #include "rclcpp/executors/executor_entities_collection.hpp" #include "rclcpp/executors/executor_entities_collector.hpp" #include "rclcpp/future_return_code.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/utilities.hpp" #include "rclcpp/visibility_control.hpp" #include "rclcpp/wait_set.hpp" namespace rclcpp { // Forward declaration is used in convenience method signature. class Node; class ExecutorImplementation; class Executor { public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor) RCLCPP_PUBLIC explicit Executor(const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions()); RCLCPP_PUBLIC virtual ~Executor(); // It is up to the implementation of Executor to implement spin. virtual void spin() = 0; RCLCPP_PUBLIC virtual void add_callback_group( rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); RCLCPP_PUBLIC virtual std::vector get_all_callback_groups(); RCLCPP_PUBLIC virtual std::vector get_manually_added_callback_groups(); RCLCPP_PUBLIC virtual std::vector get_automatically_added_callback_groups_from_nodes(); RCLCPP_PUBLIC virtual void remove_callback_group( rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify = true); RCLCPP_PUBLIC virtual void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); RCLCPP_PUBLIC virtual void add_node(std::shared_ptr node_ptr, bool notify = true); RCLCPP_PUBLIC virtual void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); RCLCPP_PUBLIC virtual void remove_node(std::shared_ptr node_ptr, bool notify = true); template void spin_node_once( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( node, std::chrono::duration_cast(timeout) ); } template void spin_node_once( std::shared_ptr node, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( node->get_node_base_interface(), std::chrono::duration_cast(timeout) ); } RCLCPP_PUBLIC virtual void spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node); RCLCPP_PUBLIC virtual void spin_node_some(std::shared_ptr node); RCLCPP_PUBLIC virtual void spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0)); RCLCPP_PUBLIC virtual void spin_node_all( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds max_duration); RCLCPP_PUBLIC virtual void spin_node_all(std::shared_ptr node, std::chrono::nanoseconds max_duration); RCLCPP_PUBLIC virtual void spin_all(std::chrono::nanoseconds max_duration); RCLCPP_PUBLIC virtual void spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); template FutureReturnCode spin_until_future_complete( const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_until_future_complete_impl( std::chrono::duration_cast(timeout), [&future](std::chrono::nanoseconds wait_time) { return future.wait_for(wait_time); } ); } RCLCPP_PUBLIC virtual void cancel(); RCLCPP_PUBLIC bool is_spinning(); protected: explicit Executor(const std::shared_ptr & context); RCLCPP_PUBLIC void spin_node_once_nanoseconds( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds timeout); RCLCPP_PUBLIC virtual FutureReturnCode spin_until_future_complete_impl( std::chrono::nanoseconds timeout, const std::function & wait_for_future); RCLCPP_PUBLIC void spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive); RCLCPP_PUBLIC void execute_any_executable(AnyExecutable & any_exec); RCLCPP_PUBLIC static void execute_subscription( rclcpp::SubscriptionBase::SharedPtr subscription); RCLCPP_PUBLIC static void execute_timer(rclcpp::TimerBase::SharedPtr timer, const std::shared_ptr & data_ptr); RCLCPP_PUBLIC static void execute_service(rclcpp::ServiceBase::SharedPtr service); RCLCPP_PUBLIC static void execute_client(rclcpp::ClientBase::SharedPtr client); RCLCPP_PUBLIC void collect_entities(); RCLCPP_PUBLIC void wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); RCLCPP_PUBLIC bool get_next_ready_executable(AnyExecutable & any_executable); RCLCPP_PUBLIC bool get_next_executable( AnyExecutable & any_executable, std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); void trigger_entity_recollect(bool notify); std::atomic_bool spinning; std::shared_ptr interrupt_guard_condition_; std::shared_ptr shutdown_guard_condition_; mutable std::mutex mutex_; std::shared_ptr context_; RCLCPP_DISABLE_COPY(Executor) RCLCPP_PUBLIC virtual void spin_once_impl(std::chrono::nanoseconds timeout); std::shared_ptr notify_waitable_; std::atomic_bool entities_need_rebuild_; rclcpp::executors::ExecutorEntitiesCollector collector_; rclcpp::WaitSet wait_set_ RCPPUTILS_TSA_GUARDED_BY(mutex_); std::optional> wait_result_ RCPPUTILS_TSA_GUARDED_BY(mutex_); rclcpp::executors::ExecutorEntitiesCollection current_collection_ RCPPUTILS_TSA_GUARDED_BY( mutex_); std::shared_ptr current_notify_waitable_ RCPPUTILS_TSA_GUARDED_BY(mutex_); rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_; std::unique_ptr impl_; }; } // namespace rclcpp #endif // RCLCPP__EXECUTOR_HPP_