Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smooth_path_action.cpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2018 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include <memory>
17 #include <string>
18 
19 #include "nav2_behavior_tree/plugins/action/smooth_path_action.hpp"
20 
21 namespace nav2_behavior_tree
22 {
23 
25  const std::string & xml_tag_name,
26  const std::string & action_name,
27  const BT::NodeConfiguration & conf)
28 : BtActionNode<nav2_msgs::action::SmoothPath>(xml_tag_name, action_name, conf)
29 {
30 }
31 
33 {
34  getInput("unsmoothed_path", goal_.path);
35  getInput("smoother_id", goal_.smoother_id);
36  double max_smoothing_duration;
37  getInput("max_smoothing_duration", max_smoothing_duration);
38  goal_.max_smoothing_duration = rclcpp::Duration::from_seconds(max_smoothing_duration);
39  getInput("check_for_collisions", goal_.check_for_collisions);
40 }
41 
43 {
44  setOutput("smoothed_path", result_.result->path);
45  setOutput("smoothing_duration", rclcpp::Duration(result_.result->smoothing_duration).seconds());
46  setOutput("was_completed", result_.result->was_completed);
47  // Set empty error code, action was successful
48  setOutput("error_code_id", ActionResult::NONE);
49  setOutput("error_msg", "");
50  return BT::NodeStatus::SUCCESS;
51 }
52 
54 {
55  setOutput("error_code_id", result_.result->error_code);
56  setOutput("error_msg", result_.result->error_msg);
57  return BT::NodeStatus::FAILURE;
58 }
59 
61 {
62  // Set empty error code, action was cancelled
63  setOutput("error_code_id", ActionResult::NONE);
64  setOutput("error_msg", "");
65  return BT::NodeStatus::SUCCESS;
66 }
67 
69 {
70  setOutput("error_code_id", ActionResult::TIMEOUT);
71  setOutput("error_msg", "Behavior Tree action client timed out waiting.");
72 }
73 
74 } // namespace nav2_behavior_tree
75 
76 #include "behaviortree_cpp/bt_factory.h"
77 BT_REGISTER_NODES(factory)
78 {
79  BT::NodeBuilder builder =
80  [](const std::string & name, const BT::NodeConfiguration & config)
81  {
82  return std::make_unique<nav2_behavior_tree::SmoothPathAction>(
83  name, "smooth_path", config);
84  };
85 
86  factory.registerBuilder<nav2_behavior_tree::SmoothPathAction>(
87  "SmoothPath", builder);
88 }
Abstract class representing an action based BT node.
A nav2_behavior_tree::BtActionNode class that wraps nav2_msgs::action::SmoothPath.
SmoothPathAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SmoothPathAction.
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation 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...
void on_tick() override
Function to perform some user-defined operation on tick.