ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
executors.hpp
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
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_HPP_
16 #define RCLCPP__EXECUTORS_HPP_
17 
18 #include <future>
19 #include <memory>
20 
21 #include "rclcpp/executors/multi_threaded_executor.hpp"
22 #include "rclcpp/executors/single_threaded_executor.hpp"
23 #include "rclcpp/executors/static_single_threaded_executor.hpp"
24 #include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
25 #include "rclcpp/node.hpp"
26 #include "rclcpp/utilities.hpp"
27 #include "rclcpp/visibility_control.hpp"
28 
29 namespace rclcpp
30 {
31 
33 
34 RCLCPP_PUBLIC
35 void
36 spin_all(
37  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
38  std::chrono::nanoseconds max_duration);
39 
40 RCLCPP_PUBLIC
41 void
42 spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration);
43 
45 
46 RCLCPP_PUBLIC
47 void
48 spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
49 
50 RCLCPP_PUBLIC
51 void
52 spin_some(rclcpp::Node::SharedPtr node_ptr);
53 
55 
56 RCLCPP_PUBLIC
57 void
58 spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
59 
60 RCLCPP_PUBLIC
61 void
62 spin(rclcpp::Node::SharedPtr node_ptr);
63 
64 namespace executors
65 {
66 
69 
71 
82 template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
84 spin_node_until_future_complete(
85  rclcpp::Executor & executor,
86  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
87  const FutureT & future,
88  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
89 {
90  // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
91  // inside a callback executed by an executor.
92  executor.add_node(node_ptr);
93  auto retcode = executor.spin_until_future_complete(future, timeout);
94  executor.remove_node(node_ptr);
95  return retcode;
96 }
97 
98 template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
99  typename TimeT = std::milli>
101 spin_node_until_future_complete(
102  rclcpp::Executor & executor,
103  std::shared_ptr<NodeT> node_ptr,
104  const FutureT & future,
105  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
106 {
107  return rclcpp::executors::spin_node_until_future_complete(
108  executor,
109  node_ptr->get_node_base_interface(),
110  future,
111  timeout);
112 }
113 
114 } // namespace executors
115 
116 template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
118 spin_until_future_complete(
119  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
120  const FutureT & future,
121  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
122 {
123  rclcpp::ExecutorOptions options;
124  options.context = node_ptr->get_context();
126  return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
127 }
128 
129 template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
130  typename TimeT = std::milli>
132 spin_until_future_complete(
133  std::shared_ptr<NodeT> node_ptr,
134  const FutureT & future,
135  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
136 {
137  return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
138 }
139 
140 } // namespace rclcpp
141 
142 #endif // RCLCPP__EXECUTORS_HPP_
Coordinate the order and timing of available communication tasks.
Definition: executor.hpp:65
FutureReturnCode spin_until_future_complete(const FutureT &future, std::chrono::duration< TimeRepT, TimeT > timeout=std::chrono::duration< TimeRepT, TimeT >(-1))
Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
Definition: executor.hpp:365
virtual RCLCPP_PUBLIC void remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
Remove a node from the executor.
Definition: executor.cpp:224
virtual RCLCPP_PUBLIC void add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify=true)
Add a node to the executor.
Definition: executor.cpp:188
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:80
Single-threaded executor implementation.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC void spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and spin the specified node.
Definition: executors.cpp:50
FutureReturnCode
Return codes to be used with spin_until_future_complete.
RCLCPP_PUBLIC void spin_all(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
Create a default single-threaded executor and execute all available work exhaustively.
Definition: executors.cpp:18
RCLCPP_PUBLIC void spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
Create a default single-threaded executor and execute any immediately available work.
Definition: executors.cpp:35
Options to be passed to the executor constructor.