Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
spin_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__SPIN_ACTION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SPIN_ACTION_HPP_
17 
18 #include <string>
19 
20 #include "nav2_behavior_tree/bt_action_node.hpp"
21 #include "nav2_msgs/action/spin.hpp"
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 
24 namespace nav2_behavior_tree
25 {
26 
32 class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
33 {
34  using Action = nav2_msgs::action::Spin;
35  using ActionResult = Action::Result;
36 
37 public:
44  SpinAction(
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 
58  void on_timeout() override;
59 
63  void initialize();
64 
69  static BT::PortsList providedPorts()
70  {
71  return providedBasicPorts(
72  {
73  BT::InputPort<double>("spin_dist", 1.57, "Spin distance"),
74  BT::InputPort<double>("time_allowance", 10.0, "Allowed time for spinning"),
75  BT::InputPort<bool>("is_recovery", true, "True if recovery"),
76  BT::InputPort<bool>("disable_collision_checks", false, "Disable collision checking"),
77  BT::OutputPort<ActionResult::_error_code_type>(
78  "error_code_id", "The spin behavior error code"),
79  BT::OutputPort<std::string>(
80  "error_msg", "The spin behavior error msg"),
81  });
82  }
83 
87  BT::NodeStatus on_success() override;
88 
92  BT::NodeStatus on_aborted() override;
93 
97  BT::NodeStatus on_cancelled() override;
98 
99 private:
100  bool is_recovery_;
101 };
102 
103 } // namespace nav2_behavior_tree
104 
105 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__SPIN_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::Spin.
Definition: spin_action.hpp:33
BT::NodeStatus on_success() override
Function to perform some user-defined operation upon successful completion of the action.
Definition: spin_action.cpp:50
void initialize()
Function to read parameters and initialize class variables.
Definition: spin_action.cpp:28
void on_tick() override
Function to perform some user-defined operation on tick.
Definition: spin_action.cpp:39
SpinAction(const std::string &xml_tag_name, const std::string &action_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::SpinAction.
Definition: spin_action.cpp:22
BT::NodeStatus on_cancelled() override
Function to perform some user-defined operation upon cancellation of the action.
Definition: spin_action.cpp:64
BT::NodeStatus on_aborted() override
Function to perform some user-defined operation upon abortion of the action.
Definition: spin_action.cpp:57
static BT::PortsList providedPorts()
Creates list of BT ports.
Definition: spin_action.hpp:69
void on_timeout() override
Function to perform work in a BT Node when the action server times out Such as setting the error code...
Definition: spin_action.cpp:71