Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smooth_path_action.hpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2019 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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SMOOTH_PATH_ACTION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SMOOTH_PATH_ACTION_HPP_
18 
19 #include <string>
20 
21 #include "nav2_msgs/action/smooth_path.hpp"
22 #include "nav_msgs/msg/path.hpp"
23 #include "nav2_behavior_tree/bt_action_node.hpp"
24 #include "nav2_ros_common/lifecycle_node.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
32 class SmoothPathAction : public nav2_behavior_tree::BtActionNode<nav2_msgs::action::SmoothPath>
33 {
34  using Action = nav2_msgs::action::SmoothPath;
35  using ActionResult = Action::Result;
36 
37 public:
45  const std::string & xml_tag_name,
46  const std::string & action_name,
47  const BT::NodeConfiguration & conf);
48 
52  void on_tick() override;
53 
57  BT::NodeStatus on_success() override;
58 
62  BT::NodeStatus on_aborted() override;
63 
67  BT::NodeStatus on_cancelled() override;
68 
73  void on_timeout() override;
74 
79  static BT::PortsList providedPorts()
80  {
81  // Register JSON definitions for the types used in the ports
82  BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
83 
84  return providedBasicPorts(
85  {
86  BT::InputPort<nav_msgs::msg::Path>("unsmoothed_path", "Path to be smoothed"),
87  BT::InputPort<double>("max_smoothing_duration", 3.0, "Maximum smoothing duration"),
88  BT::InputPort<bool>(
89  "check_for_collisions", false,
90  "If true collision check will be performed after smoothing"),
91  BT::InputPort<std::string>("smoother_id", ""),
92  BT::OutputPort<nav_msgs::msg::Path>(
93  "smoothed_path",
94  "Path smoothed by SmootherServer node"),
95  BT::OutputPort<double>("smoothing_duration", "Time taken to smooth path"),
96  BT::OutputPort<bool>(
97  "was_completed", "True if smoothing was not interrupted by time limit"),
98  BT::OutputPort<ActionResult::_error_code_type>(
99  "error_code_id", "The smooth path error code"),
100  BT::OutputPort<std::string>(
101  "error_msg", "The smooth path error msg"),
102  });
103  }
104 };
105 
106 } // namespace nav2_behavior_tree
107 
108 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SMOOTH_PATH_ACTION_HPP_
Abstract class representing an action based BT node.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Any subclass of BtActionNode that accepts parameters must provide a providedPorts method and call pro...
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.
static BT::PortsList providedPorts()
Creates list of BT ports.
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.