Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
drive_on_heading_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 <string>
16 #include <memory>
17 
18 #include "nav2_behavior_tree/plugins/action/drive_on_heading_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<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf)
28 {
29 }
30 
32 {
33  double dist;
34  getInput("dist_to_travel", dist);
35  double speed;
36  getInput("speed", speed);
37  double time_allowance;
38  getInput("time_allowance", time_allowance);
39  bool disable_collision_checks;
40  getInput("disable_collision_checks", disable_collision_checks);
41 
42  // Populate the input message
43  goal_.target.x = dist;
44  goal_.target.y = 0.0;
45  goal_.target.z = 0.0;
46  goal_.speed = speed;
47  goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
48  goal_.disable_collision_checks = disable_collision_checks;
49 }
50 
52 {
53  if (!BT::isStatusActive(status())) {
54  initialize();
55  }
56 }
57 
59 {
60  setOutput("error_code_id", ActionResult::NONE);
61  setOutput("error_msg", "");
62  return BT::NodeStatus::SUCCESS;
63 }
64 
66 {
67  setOutput("error_code_id", result_.result->error_code);
68  setOutput("error_msg", result_.result->error_msg);
69  return BT::NodeStatus::FAILURE;
70 }
71 
73 {
74  setOutput("error_code_id", ActionResult::NONE);
75  setOutput("error_msg", "");
76  return BT::NodeStatus::SUCCESS;
77 }
78 
80 {
81  setOutput("error_code_id", ActionResult::TIMEOUT);
82  setOutput("error_msg", "Behavior Tree action client timed out waiting.");
83 }
84 
85 } // namespace nav2_behavior_tree
86 
87 #include "behaviortree_cpp/bt_factory.h"
88 BT_REGISTER_NODES(factory)
89 {
90  BT::NodeBuilder builder =
91  [](const std::string & name, const BT::NodeConfiguration & config)
92  {
93  return std::make_unique<nav2_behavior_tree::DriveOnHeadingAction>(
94  name, "drive_on_heading", config);
95  };
96 
97  factory.registerBuilder<nav2_behavior_tree::DriveOnHeadingAction>("DriveOnHeading", builder);
98 }
Abstract class representing an action based BT node.
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::DriveOnHeading.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
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.
DriveOnHeadingAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::DriveOnHeadingAction.
void on_tick() override
Function to perform some user-defined operation on tick.
void initialize()
Function to read parameters and initialize class variables.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.