Nav2 Navigation Stack - humble  humble
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_v3/condition_node.h"
23 #include "tf2_ros/buffer.h"
24 
25 namespace nav2_behavior_tree
26 {
27 
32 class GoalReachedCondition : public BT::ConditionNode
33 {
34 public:
41  const std::string & condition_name,
42  const BT::NodeConfiguration & conf);
43 
44  GoalReachedCondition() = delete;
45 
49  ~GoalReachedCondition() override;
50 
55  BT::NodeStatus tick() override;
56 
60  void initialize();
61 
66  bool isGoalReached();
67 
72  static BT::PortsList providedPorts()
73  {
74  return {
75  BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination"),
76  BT::InputPort<std::string>("global_frame", std::string("map"), "Global frame"),
77  BT::InputPort<std::string>("robot_base_frame", std::string("base_link"), "Robot base frame")
78  };
79  }
80 
81 protected:
85  void cleanup()
86  {}
87 
88 private:
89  rclcpp::Node::SharedPtr node_;
90  std::shared_ptr<tf2_ros::Buffer> tf_;
91 
92  bool initialized_;
93  double goal_reached_tol_;
94  std::string global_frame_;
95  std::string robot_base_frame_;
96  double transform_tolerance_;
97 };
98 
99 } // namespace nav2_behavior_tree
100 
101 #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.