Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
compute_path_to_pose_action.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_ACTION_HPP_
17 
18 #include <string>
19 
20 #include "nav2_msgs/action/compute_path_to_pose.hpp"
21 #include "nav_msgs/msg/path.hpp"
22 #include "nav2_behavior_tree/bt_action_node.hpp"
23 #include "nav2_ros_common/lifecycle_node.hpp"
24 
25 namespace nav2_behavior_tree
26 {
27 
33 class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePathToPose>
34 {
35  using Action = nav2_msgs::action::ComputePathToPose;
36  using ActionResult = Action::Result;
37 
38 public:
46  const std::string & xml_tag_name,
47  const std::string & action_name,
48  const BT::NodeConfiguration & conf);
49 
53  void on_tick() override;
54 
58  BT::NodeStatus on_success() override;
59 
63  BT::NodeStatus on_aborted() override;
64 
68  BT::NodeStatus on_cancelled() override;
69 
74  void on_timeout() override;
75 
79  void halt() override;
80 
85  static BT::PortsList providedPorts()
86  {
87  // Register JSON definitions for the types used in the ports
88  BT::RegisterJsonDefinition<nav_msgs::msg::Path>();
89  BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
90 
91  return providedBasicPorts(
92  {
93  BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
94  BT::InputPort<geometry_msgs::msg::PoseStamped>(
95  "start",
96  "Used as the planner start pose instead of the current robot pose, if use_start is"
97  " not false (i.e. not provided or set to true)"),
98  BT::InputPort<bool>(
99  "use_start", "For using or not using (i.e. ignoring) the provided start pose"),
100  BT::InputPort<std::string>(
101  "planner_id", "",
102  "Mapped name to the planner plugin type to use"),
103  BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputePathToPose node"),
104  BT::OutputPort<ActionResult::_error_code_type>(
105  "error_code_id", "The compute path to pose error code"),
106  BT::OutputPort<std::string>(
107  "error_msg", "The compute path to pose error msg"),
108  });
109  }
110 };
111 
112 } // namespace nav2_behavior_tree
113 
114 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__COMPUTE_PATH_TO_POSE_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::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.
static BT::PortsList providedPorts()
Creates list of BT ports.
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.