Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
bt_cancel_action_node.hpp
1 // Copyright (c) 2022 Neobotix GmbH
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 NAV2_BEHAVIOR_TREE__BT_CANCEL_ACTION_NODE_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_CANCEL_ACTION_NODE_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <chrono>
21 
22 #include "behaviortree_cpp/action_node.h"
23 #include "nav2_util/node_utils.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "nav2_behavior_tree/bt_utils.hpp"
26 
27 namespace nav2_behavior_tree
28 {
29 
30 using namespace std::chrono_literals; // NOLINT
31 
36 template<class ActionT>
37 class BtCancelActionNode : public BT::ActionNodeBase
38 {
39 public:
47  const std::string & xml_tag_name,
48  const std::string & action_name,
49  const BT::NodeConfiguration & conf)
50  : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name)
51  {
52  node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");
53  callback_group_ = node_->create_callback_group(
54  rclcpp::CallbackGroupType::MutuallyExclusive,
55  false);
56  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 
58  // Get the required items from the blackboard
59  getInputOrBlackboard("server_timeout", server_timeout_);
60  wait_for_service_timeout_ =
61  config().blackboard->template get<std::chrono::milliseconds>("wait_for_service_timeout");
62 
63  std::string remapped_action_name;
64  if (getInput("server_name", remapped_action_name)) {
65  action_name_ = remapped_action_name;
66  }
67  createActionClient(action_name_);
68 
69  // Give the derive class a chance to do any initialization
70  RCLCPP_DEBUG(
71  node_->get_logger(), "\"%s\" BtCancelActionNode initialized",
72  xml_tag_name.c_str());
73  }
74 
75  BtCancelActionNode() = delete;
76 
77  virtual ~BtCancelActionNode()
78  {
79  }
80 
85  void createActionClient(const std::string & action_name)
86  {
87  // Now that we have the ROS node to use, create the action client for this BT action
88  action_client_ = rclcpp_action::create_client<ActionT>(node_, action_name, callback_group_);
89 
90  // Make sure the server is actually there before continuing
91  RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
92  if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
93  RCLCPP_ERROR(
94  node_->get_logger(), "\"%s\" action server not available after waiting for %.2fs",
95  action_name.c_str(), wait_for_service_timeout_.count() / 1000.0);
96  throw std::runtime_error(
97  std::string("Action server ") + action_name +
98  std::string(" not available"));
99  }
100  }
101 
108  static BT::PortsList providedBasicPorts(BT::PortsList addition)
109  {
110  BT::PortsList basic = {
111  BT::InputPort<std::string>("server_name", "Action server name"),
112  BT::InputPort<std::chrono::milliseconds>("server_timeout")
113  };
114  basic.insert(addition.begin(), addition.end());
115 
116  return basic;
117  }
118 
119  void halt() override
120  {
121  }
122 
127  static BT::PortsList providedPorts()
128  {
129  return providedBasicPorts({});
130  }
131 
136  BT::NodeStatus tick() override
137  {
138  // setting the status to RUNNING to notify the BT Loggers (if any)
139  setStatus(BT::NodeStatus::RUNNING);
140 
141  // Cancel all the goals specified before 10ms from current time
142  // to avoid async communication error
143 
144  rclcpp::Time goal_expiry_time = node_->now() - std::chrono::milliseconds(10);
145 
146  auto future_cancel = action_client_->async_cancel_goals_before(goal_expiry_time);
147 
148  if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) !=
149  rclcpp::FutureReturnCode::SUCCESS)
150  {
151  RCLCPP_ERROR(
152  node_->get_logger(),
153  "Failed to cancel the action server for %s", action_name_.c_str());
154  return BT::NodeStatus::FAILURE;
155  }
156  return BT::NodeStatus::SUCCESS;
157  }
158 
159 protected:
160  std::string action_name_;
161  typename std::shared_ptr<rclcpp_action::Client<ActionT>> action_client_;
162 
163  // The node that will be used for any ROS operations
164  rclcpp::Node::SharedPtr node_;
165  rclcpp::CallbackGroup::SharedPtr callback_group_;
166  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
167 
168  // The timeout value while waiting for response from a server when a
169  // new action goal is canceled
170  std::chrono::milliseconds server_timeout_;
171  // The timeout value for waiting for a service to response
172  std::chrono::milliseconds wait_for_service_timeout_;
173 };
174 
175 } // namespace nav2_behavior_tree
176 
177 #endif // NAV2_BEHAVIOR_TREE__BT_CANCEL_ACTION_NODE_HPP_
Abstract class representing an action for cancelling BT node.
void createActionClient(const std::string &action_name)
Create instance of an action client.
BtCancelActionNode(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A nav2_behavior_tree::BtCancelActionNode constructor.
BT::NodeStatus tick() override
The main override required by a BT action.
static BT::PortsList providedPorts()
Creates list of BT ports.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtCancelActionNode that accepts parameters must provide a providedPorts method and ca...