-
Notifications
You must be signed in to change notification settings - Fork 527
Expand file tree
/
Copy pathexecutors.cpp
More file actions
69 lines (62 loc) · 2.13 KB
/
executors.cpp
File metadata and controls
69 lines (62 loc) · 2.13 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
// Copyright 2015 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.
#include "rclcpp/executors.hpp"
#include "rcpputils/compile_warnings.hpp"
void
rclcpp::spin_all(
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr,
std::chrono::nanoseconds max_duration)
{
rclcpp::ExecutorOptions options;
options.context = node_ptr->get_context();
rclcpp::executors::SingleThreadedExecutor exec(options);
exec.spin_node_all(node_ptr, max_duration);
}
void
rclcpp::spin_some(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr)
{
rclcpp::ExecutorOptions options;
options.context = node_ptr->get_context();
rclcpp::executors::SingleThreadedExecutor exec(options);
exec.spin_node_some(node_ptr);
}
void
rclcpp::spin(const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr & node_ptr)
{
rclcpp::ExecutorOptions options;
options.context = node_ptr->get_context();
rclcpp::executors::SingleThreadedExecutor exec(options);
exec.add_node(node_ptr);
exec.spin();
exec.remove_node(node_ptr);
}
void
rclcpp::spin(const rclcpp::Node::SharedPtr & node_ptr)
{
rclcpp::spin(node_ptr->get_node_base_interface());
}
void
rclcpp::spin_all(const rclcpp::Node::SharedPtr & node_ptr, std::chrono::nanoseconds max_duration)
{
RCPPUTILS_DEPRECATION_WARNING_OFF_START
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
}
void
rclcpp::spin_some(const rclcpp::Node::SharedPtr & node_ptr)
{
RCPPUTILS_DEPRECATION_WARNING_OFF_START
rclcpp::spin_some(node_ptr->get_node_base_interface());
RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
}