Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
drive_on_heading_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__DRIVE_ON_HEADING_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__DRIVE_ON_HEADING_ACTION_HPP_
17 
18 #include <string>
19 
20 #include "nav2_behavior_tree/bt_action_node.hpp"
21 #include "nav2_msgs/action/drive_on_heading.hpp"
22 
23 namespace nav2_behavior_tree
24 {
25 
31 class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeading>
32 {
33  using Action = nav2_msgs::action::DriveOnHeading;
34  using ActionResult = Action::Result;
35 
36 public:
44  const std::string & xml_tag_name,
45  const std::string & action_name,
46  const BT::NodeConfiguration & conf);
47 
51  void initialize();
52 
57  static BT::PortsList providedPorts()
58  {
59  return providedBasicPorts(
60  {
61  BT::InputPort<double>("dist_to_travel", 0.15, "Distance to travel"),
62  BT::InputPort<double>("speed", 0.025, "Speed at which to travel"),
63  BT::InputPort<double>("time_allowance", 10.0, "Allowed time for driving on heading"),
64  BT::InputPort<bool>("disable_collision_checks", false, "Disable collision checking"),
65  BT::OutputPort<Action::Result::_error_code_type>(
66  "error_code_id", "The drive on heading behavior server error code"),
67  BT::OutputPort<std::string>(
68  "error_msg", "The drive on heading behavior server error msg"),
69  });
70  }
71 
75  void on_tick() override;
76 
80  BT::NodeStatus on_success() override;
81 
85  BT::NodeStatus on_aborted() override;
86 
90  BT::NodeStatus on_cancelled() override;
91 
96  void on_timeout() override;
97 };
98 
99 } // namespace nav2_behavior_tree
100 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__DRIVE_ON_HEADING_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::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.
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.