ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
static_single_threaded_executor.hpp
1 // Copyright 2019 Nobleo Technology
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__EXECUTORS__STATIC_SINGLE_THREADED_EXECUTOR_HPP_
16 #define RCLCPP__EXECUTORS__STATIC_SINGLE_THREADED_EXECUTOR_HPP_
17 
18 #include <chrono>
19 #include <cassert>
20 #include <cstdlib>
21 #include <memory>
22 #include <vector>
23 #include <string>
24 
25 #include "rmw/rmw.h"
26 
27 #include "rclcpp/executor.hpp"
28 #include "rclcpp/executors/static_executor_entities_collector.hpp"
29 #include "rclcpp/experimental/executable_list.hpp"
30 #include "rclcpp/macros.hpp"
31 #include "rclcpp/memory_strategies.hpp"
32 #include "rclcpp/node.hpp"
33 #include "rclcpp/rate.hpp"
34 #include "rclcpp/utilities.hpp"
35 #include "rclcpp/visibility_control.hpp"
36 
37 namespace rclcpp
38 {
39 namespace executors
40 {
41 
43 
59 {
60 public:
61  RCLCPP_SMART_PTR_DEFINITIONS(StaticSingleThreadedExecutor)
62 
63 
64  RCLCPP_PUBLIC
67 
69  RCLCPP_PUBLIC
71 
73 
78  RCLCPP_PUBLIC
79  void
80  spin() override;
81 
83 
96  RCLCPP_PUBLIC
97  void
98  spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0)) override;
99 
101 
115  RCLCPP_PUBLIC
116  void
117  spin_all(std::chrono::nanoseconds max_duration) override;
118 
120 
123  RCLCPP_PUBLIC
124  void
126  rclcpp::CallbackGroup::SharedPtr group_ptr,
127  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
128  bool notify = true) override;
129 
131 
134  RCLCPP_PUBLIC
135  void
137  rclcpp::CallbackGroup::SharedPtr group_ptr,
138  bool notify = true) override;
139 
141 
144  RCLCPP_PUBLIC
145  void
146  add_node(
147  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
148  bool notify = true) override;
149 
151 
154  RCLCPP_PUBLIC
155  void
156  add_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true) override;
157 
159 
162  RCLCPP_PUBLIC
163  void
164  remove_node(
165  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
166  bool notify = true) override;
167 
169 
172  RCLCPP_PUBLIC
173  void
174  remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true) override;
175 
176  RCLCPP_PUBLIC
177  std::vector<rclcpp::CallbackGroup::WeakPtr>
178  get_all_callback_groups() override;
179 
181 
184  RCLCPP_PUBLIC
185  std::vector<rclcpp::CallbackGroup::WeakPtr>
187 
189 
192  RCLCPP_PUBLIC
193  std::vector<rclcpp::CallbackGroup::WeakPtr>
195 
196 protected:
202  RCLCPP_PUBLIC
203  bool
204  execute_ready_executables(bool spin_once = false);
205 
206  RCLCPP_PUBLIC
207  void
208  spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive);
209 
210  RCLCPP_PUBLIC
211  void
212  spin_once_impl(std::chrono::nanoseconds timeout) override;
213 
214 private:
215  RCLCPP_DISABLE_COPY(StaticSingleThreadedExecutor)
216 
217  StaticExecutorEntitiesCollector::SharedPtr entities_collector_;
218 };
219 
220 } // namespace executors
221 } // namespace rclcpp
222 
223 #endif // RCLCPP__EXECUTORS__STATIC_SINGLE_THREADED_EXECUTOR_HPP_
Coordinate the order and timing of available communication tasks.
Definition: executor.hpp:66
RCLCPP_PUBLIC void spin_some(std::chrono::nanoseconds max_duration=std::chrono::nanoseconds(0)) override
Static executor implementation of spin some.
RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_all_callback_groups() override
Get callback groups that belong to executor.
RCLCPP_PUBLIC void spin() override
Static executor implementation of spin.
RCLCPP_PUBLIC void add_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true) override
Add a callback group to an executor.
RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_manually_added_callback_groups() override
Get callback groups that belong to executor.
virtual RCLCPP_PUBLIC ~StaticSingleThreadedExecutor()
Default destrcutor.
RCLCPP_PUBLIC void spin_all(std::chrono::nanoseconds max_duration) override
Static executor implementation of spin all.
RCLCPP_PUBLIC void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true) override
Remove a node from the executor.
RCLCPP_PUBLIC bool execute_ready_executables(bool spin_once=false)
Executes ready executables from wait set.
RCLCPP_PUBLIC void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true) override
Add a node to the executor.
RCLCPP_PUBLIC std::vector< rclcpp::CallbackGroup::WeakPtr > get_automatically_added_callback_groups_from_nodes() override
Get callback groups that belong to executor.
RCLCPP_PUBLIC void remove_callback_group(rclcpp::CallbackGroup::SharedPtr group_ptr, bool notify=true) override
Remove callback group from the executor.
RCLCPP_PUBLIC StaticSingleThreadedExecutor(const rclcpp::ExecutorOptions &options=rclcpp::ExecutorOptions())
Default constructor. See the default constructor for Executor.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Options to be passed to the executor constructor.