ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
node_waitables.cpp
1 // Copyright 2018 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/node_interfaces/node_waitables.hpp"
16 
17 #include <string>
18 
20 
21 NodeWaitables::NodeWaitables(rclcpp::node_interfaces::NodeBaseInterface * node_base)
22 : node_base_(node_base)
23 {}
24 
25 NodeWaitables::~NodeWaitables()
26 {}
27 
28 void
29 NodeWaitables::add_waitable(
30  rclcpp::Waitable::SharedPtr waitable_ptr,
31  rclcpp::CallbackGroup::SharedPtr group)
32 {
33  if (group) {
34  if (!node_base_->callback_group_in_node(group)) {
35  // TODO(jacobperron): use custom exception
36  throw std::runtime_error("Cannot create waitable, group not in node.");
37  }
38  } else {
39  group = node_base_->get_default_callback_group();
40  }
41 
42  group->add_waitable(waitable_ptr);
43 
44  // Notify the executor that a new waitable was created using the parent Node.
45  auto & node_gc = node_base_->get_notify_guard_condition();
46  try {
47  node_gc.trigger();
48  group->trigger_notify_guard_condition();
49  } catch (const rclcpp::exceptions::RCLError & ex) {
50  throw std::runtime_error(
51  std::string("failed to notify wait set on waitable creation: ") + ex.what());
52  }
53 }
54 
55 void
57  rclcpp::Waitable::SharedPtr waitable_ptr,
58  rclcpp::CallbackGroup::SharedPtr group) noexcept
59 {
60  if (group) {
61  if (!node_base_->callback_group_in_node(group)) {
62  return;
63  }
64  group->remove_waitable(waitable_ptr);
65  } else {
66  node_base_->get_default_callback_group()->remove_waitable(waitable_ptr);
67  }
68 }
RCLCPP_PUBLIC void trigger()
Notify the wait set waiting on this condition, if any, that the condition had been met.
Created when the return code does not match one of the other specialized exceptions.
Definition: exceptions.hpp:153
Pure virtual interface class for the NodeBase part of the Node API.
virtual RCLCPP_PUBLIC bool callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group)=0
Return true if the given callback group is associated with this node.
virtual RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr get_default_callback_group()=0
Return the default callback group.
virtual RCLCPP_PUBLIC rclcpp::GuardCondition & get_notify_guard_condition()=0
Return a guard condition that should be notified when the internal node state changes.
Implementation of the NodeWaitables part of the Node API.
RCLCPP_PUBLIC void remove_waitable(rclcpp::Waitable::SharedPtr waitable_ptr, rclcpp::CallbackGroup::SharedPtr group) noexcept override