Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
dock_robot.cpp
1 // Copyright (c) 2024 Open Navigation LLC
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 "opennav_docking_bt/dock_robot.hpp"
19 
20 namespace opennav_docking_bt
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  // Get core inputs about what to perform
34  [[maybe_unused]] auto res = getInput("use_dock_id", goal_.use_dock_id);
35  if (goal_.use_dock_id) {
36  getInput("dock_id", goal_.dock_id);
37  } else {
38  getInput("dock_pose", goal_.dock_pose);
39  getInput("dock_type", goal_.dock_type);
40  getInput("max_staging_time", goal_.max_staging_time);
41  }
42  getInput("navigate_to_staging_pose", goal_.navigate_to_staging_pose);
43 }
44 
46 {
47  setOutput("success", result_.result->success);
48  setOutput("num_retries", result_.result->num_retries);
49  setOutput("error_code_id", ActionResult::NONE);
50  setOutput("error_msg", "");
51  return BT::NodeStatus::SUCCESS;
52 }
53 
55 {
56  setOutput("success", result_.result->success);
57  setOutput("num_retries", result_.result->num_retries);
58  setOutput("error_code_id", result_.result->error_code);
59  setOutput("error_msg", result_.result->error_msg);
60  return BT::NodeStatus::FAILURE;
61 }
62 
64 {
65  setOutput("error_code_id", ActionResult::NONE);
66  setOutput("error_msg", "");
67  return BT::NodeStatus::SUCCESS;
68 }
69 
71 {
72  setOutput("error_code_id", ActionResult::TIMEOUT);
73  setOutput("error_msg", "Behavior Tree action client timed out waiting.");
74 }
75 
77 {
78  BtActionNode::halt();
79 }
80 
81 } // namespace opennav_docking_bt
82 
83 #include "behaviortree_cpp/bt_factory.h"
84 BT_REGISTER_NODES(factory)
85 {
86  BT::NodeBuilder builder =
87  [](const std::string & name, const BT::NodeConfiguration & config)
88  {
89  return std::make_unique<opennav_docking_bt::DockRobotAction>(
90  name, "dock_robot", config);
91  };
92 
93  factory.registerBuilder<opennav_docking_bt::DockRobotAction>(
94  "DockRobot", builder);
95 }
nav2_behavior_tree::BtActionNode class that wraps opnav2_msgsennav_docking_msgs/DockRobot
Definition: dock_robot.hpp:35
void on_tick() override
Function to perform some user-defined operation on tick.
Definition: dock_robot.cpp:31
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
Definition: dock_robot.cpp:63
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
Definition: dock_robot.cpp:54
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
Definition: dock_robot.cpp:45
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
Definition: dock_robot.cpp:70
void halt() override
Override required by the a BT action. Cancel the action and set the path output.
Definition: dock_robot.cpp:76
DockRobotAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for opennav_docking_bt::DockRobotAction.
Definition: dock_robot.cpp:23