Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
compute_path_to_pose_action.cpp
1 // Copyright (c) 2018 Intel Corporation
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 <memory>
16 #include <string>
17 
18 #include "nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp"
19 
20 namespace nav2_behavior_tree
21 {
22 
24  const std::string & xml_tag_name,
25  const std::string & action_name,
26  const BT::NodeConfiguration & conf)
27 : BtActionNode<Action>(xml_tag_name, action_name, conf)
28 {
29 }
30 
32 {
33  getInput("goal", goal_.goal);
34  getInput("planner_id", goal_.planner_id);
35 
36  // if "use_start" is provided try to enforce it (true or false), but we cannot enforce true if
37  // start is not provided
38  goal_.use_start = false;
39  if (getInput("use_start", goal_.use_start)) {
40  if (goal_.use_start && !getInput("start", goal_.start)) {
41  // in case we don't have a "start" pose
42  goal_.use_start = false;
43  RCLCPP_ERROR(
44  node_->get_logger(),
45  "use_start is set to true but no start pose was provided, falling back to default "
46  "behavior, i.e. using the current robot pose");
47  }
48  } else {
49  // else if "use_start" is not provided, but "start" is, then use it in order to not change
50  // the legacy behavior
51  if (getInput("start", goal_.start)) {
52  goal_.use_start = true;
53  }
54  }
55 }
56 
58 {
59  setOutput("path", result_.result->path);
60  // Set empty error code, action was successful
61  setOutput("error_code_id", ActionResult::NONE);
62  setOutput("error_msg", "");
63  return BT::NodeStatus::SUCCESS;
64 }
65 
67 {
68  nav_msgs::msg::Path empty_path;
69  setOutput("path", empty_path);
70  setOutput("error_code_id", result_.result->error_code);
71  setOutput("error_msg", result_.result->error_msg);
72  return BT::NodeStatus::FAILURE;
73 }
74 
76 {
77  nav_msgs::msg::Path empty_path;
78  setOutput("path", empty_path);
79  // Set empty error code, action was cancelled
80  setOutput("error_code_id", ActionResult::NONE);
81  setOutput("error_msg", "");
82  return BT::NodeStatus::SUCCESS;
83 }
84 
86 {
87  setOutput("error_code_id", ActionResult::TIMEOUT);
88  setOutput("error_msg", "Behavior Tree action client timed out waiting.");
89 }
90 
92 {
93  nav_msgs::msg::Path empty_path;
94  setOutput("path", empty_path);
95  // DO NOT reset "error_code_id" output port, we want to read it later
96  // DO NOT reset "error_msg" output port, we want to read it later
98 }
99 
100 } // namespace nav2_behavior_tree
101 
102 #include "behaviortree_cpp/bt_factory.h"
103 BT_REGISTER_NODES(factory)
104 {
105  BT::NodeBuilder builder =
106  [](const std::string & name, const BT::NodeConfiguration & config)
107  {
108  return std::make_unique<nav2_behavior_tree::ComputePathToPoseAction>(
109  name, "compute_path_to_pose", config);
110  };
111 
112  factory.registerBuilder<nav2_behavior_tree::ComputePathToPoseAction>(
113  "ComputePathToPose", builder);
114 }
Abstract class representing an action based BT node.
void halt() override
The other (optional) override required by a BT action. In this case, we make sure to cancel the ROS2 ...
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::ComputePathToPose.
void on_tick() override
Function to perform some user-defined operation on tick.
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
ComputePathToPoseAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ComputePathToPoseAction.
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.