ROS 2 rclcpp + rcl - rolling  rolling-b14af74a
ROS 2 C++ Client Library with ROS Client Library
executors.cpp
1 // Copyright 2015 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 #include "rclcpp/executors.hpp"
16 #include "rcpputils/compile_warnings.hpp"
17 
18 void
20  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
21  std::chrono::nanoseconds max_duration)
22 {
24  options.context = node_ptr->get_context();
26  exec.spin_node_all(node_ptr, max_duration);
27 }
28 
29 void
30 rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
31 {
33  options.context = node_ptr->get_context();
35  exec.spin_node_some(node_ptr);
36 }
37 
38 void
39 rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
40 {
42  options.context = node_ptr->get_context();
44  exec.add_node(node_ptr);
45  exec.spin();
46  exec.remove_node(node_ptr);
47 }
48 
49 void
50 rclcpp::spin(rclcpp::Node::SharedPtr node_ptr)
51 {
52  rclcpp::spin(node_ptr->get_node_base_interface());
53 }
54 
55 void
56 rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
57 {
58  RCPPUTILS_DEPRECATION_WARNING_OFF_START
59  rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
60  RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
61 }
62 
63 void
64 rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
65 {
66  RCPPUTILS_DEPRECATION_WARNING_OFF_START
67  rclcpp::spin_some(node_ptr->get_node_base_interface());
68  RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
69 }
virtual RCLCPP_PUBLIC void spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node)
Add a node, complete all immediately available work, and remove the node.
Definition: executor.cpp:314
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:230
virtual RCLCPP_PUBLIC void spin_node_all(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, std::chrono::nanoseconds max_duration)
Add a node, complete all immediately available work exhaustively, and remove the node.
Definition: executor.cpp:333
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:189
Single-threaded executor implementation.
RCLCPP_PUBLIC void spin() override
Single-threaded implementation of spin.
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:39
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:19
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:30
Options to be passed to the executor constructor.