Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
goal_reached_condition.hpp
1 // Copyright (c) 2019 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__CONDITION__GOAL_REACHED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GOAL_REACHED_CONDITION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "behaviortree_cpp/condition_node.h"
23 #include "tf2_ros/buffer.h"
24 #include "nav2_behavior_tree/bt_utils.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
33 class GoalReachedCondition : public BT::ConditionNode
34 {
35 public:
42  const std::string & condition_name,
43  const BT::NodeConfiguration & conf);
44 
45  GoalReachedCondition() = delete;
46 
50  ~GoalReachedCondition() override;
51 
56  BT::NodeStatus tick() override;
57 
61  void initialize();
62 
67  bool isGoalReached();
68 
73  static BT::PortsList providedPorts()
74  {
75  return {
76  BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination"),
77  BT::InputPort<std::string>("global_frame", "Global frame"),
78  BT::InputPort<std::string>("robot_base_frame", "Robot base frame")
79  };
80  }
81 
82 protected:
86  void cleanup()
87  {}
88 
89 private:
90  rclcpp::Node::SharedPtr node_;
91  std::shared_ptr<tf2_ros::Buffer> tf_;
92 
93  double goal_reached_tol_;
94  double transform_tolerance_;
95  std::string robot_base_frame_;
96 };
97 
98 } // namespace nav2_behavior_tree
99 
100 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GOAL_REACHED_CONDITION_HPP_
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise.
static BT::PortsList providedPorts()
Creates list of BT ports.
void initialize()
Function to read parameters and initialize class variables.
BT::NodeStatus tick() override
The main override required by a BT action.
~GoalReachedCondition() override
A destructor for nav2_behavior_tree::GoalReachedCondition.
bool isGoalReached()
Checks if the current robot pose lies within a given distance from the goal.