15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GOAL_REACHED_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GOAL_REACHED_CONDITION_HPP_
21 #include "rclcpp/rclcpp.hpp"
22 #include "behaviortree_cpp_v3/condition_node.h"
23 #include "tf2_ros/buffer.h"
25 namespace nav2_behavior_tree
41 const std::string & condition_name,
42 const BT::NodeConfiguration & conf);
55 BT::NodeStatus
tick()
override;
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")
89 rclcpp::Node::SharedPtr node_;
90 std::shared_ptr<tf2_ros::Buffer> tf_;
93 double goal_reached_tol_;
94 std::string global_frame_;
95 std::string robot_base_frame_;
96 double transform_tolerance_;
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.
void cleanup()
Cleanup function.
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.