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/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"
29 namespace nav2_behavior_tree
47 const std::string & condition_name,
48 const BT::NodeConfiguration & conf);
61 BT::NodeStatus
tick()
override;
81 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
84 BT::InputPort<geometry_msgs::msg::PoseStamped>(
"goal",
"Destination"),
85 BT::InputPort<std::string>(
"robot_base_frame",
"Robot base frame")
97 rclcpp::Node::SharedPtr node_;
98 std::shared_ptr<tf2_ros::Buffer> tf_;
100 double goal_reached_tol_;
101 double transform_tolerance_;
102 std::string robot_base_frame_;
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.