Nav2 Navigation Stack - kilted  kilted
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 "behaviortree_cpp/json_export.h"
24 #include "nav2_behavior_tree/bt_utils.hpp"
25 #include "nav2_behavior_tree/json_utils.hpp"
26 #include "tf2_ros/buffer.h"
27 
28 
29 namespace nav2_behavior_tree
30 {
31 
38 class GoalReachedCondition : public BT::ConditionNode
39 {
40 public:
47  const std::string & condition_name,
48  const BT::NodeConfiguration & conf);
49 
50  GoalReachedCondition() = delete;
51 
55  ~GoalReachedCondition() override;
56 
61  BT::NodeStatus tick() override;
62 
66  void initialize();
67 
72  bool isGoalReached();
73 
78  static BT::PortsList providedPorts()
79  {
80  // Register JSON definitions for the types used in the ports
81  BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
82 
83  return {
84  BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination"),
85  BT::InputPort<std::string>("robot_base_frame", "Robot base frame")
86  };
87  }
88 
89 protected:
93  void cleanup()
94  {}
95 
96 private:
97  rclcpp::Node::SharedPtr node_;
98  std::shared_ptr<tf2_ros::Buffer> tf_;
99 
100  double goal_reached_tol_;
101  double transform_tolerance_;
102  std::string robot_base_frame_;
103 };
104 
105 } // namespace nav2_behavior_tree
106 
107 #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.