ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
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/experimental/executors/events_executor/events_executor.hpp"
24 #include "rclcpp/node.hpp"
25 #include "rclcpp/utilities.hpp"
26 #include "rclcpp/visibility_control.hpp"
27 
28 namespace rclcpp
29 {
30 
32 
33 RCLCPP_PUBLIC
34 void
35 spin_all(
36  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
37  std::chrono::nanoseconds max_duration);
38 
39 RCLCPP_PUBLIC
40 void
41 spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration);
42 
44 
45 RCLCPP_PUBLIC
46 void
47 spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
48 
49 RCLCPP_PUBLIC
50 void
51 spin_some(rclcpp::Node::SharedPtr node_ptr);
52 
54 
55 RCLCPP_PUBLIC
56 void
57 spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
58 
59 RCLCPP_PUBLIC
60 void
61 spin(rclcpp::Node::SharedPtr node_ptr);
62 
63 namespace executors
64 {
65 
68 
70 
81 template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
83 spin_node_until_future_complete(
84  rclcpp::Executor & executor,
85  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
86  const FutureT & future,
87  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
88 {
89  // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
90  // inside a callback executed by an executor.
91  executor.add_node(node_ptr);
92  auto retcode = executor.spin_until_future_complete(future, timeout);
93  executor.remove_node(node_ptr);
94  return retcode;
95 }
96 
97 template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
98  typename TimeT = std::milli>
100 spin_node_until_future_complete(
101  rclcpp::Executor & executor,
102  std::shared_ptr<NodeT> node_ptr,
103  const FutureT & future,
104  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
105 {
106  return rclcpp::executors::spin_node_until_future_complete(
107  executor,
108  node_ptr->get_node_base_interface(),
109  future,
110  timeout);
111 }
112 
113 } // namespace executors
114 
115 template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
117 spin_until_future_complete(
118  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
119  const FutureT & future,
120  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
121 {
122  rclcpp::ExecutorOptions options;
123  options.context = node_ptr->get_context();
125  return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
126 }
127 
128 template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
129  typename TimeT = std::milli>
131 spin_until_future_complete(
132  std::shared_ptr<NodeT> node_ptr,
133  const FutureT & future,
134  std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
135 {
136  return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
137 }
138 
139 } // namespace rclcpp
140 
141 #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:377
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:223
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:187
Node is the single point of entry for creating publishers and subscribers.
Definition: node.hpp:81
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.