18 #include "nav2_util/robot_utils.hpp"
19 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "nav2_util/node_utils.hpp"
22 #include "nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp"
24 namespace nav2_behavior_tree
27 GoalReachedCondition::GoalReachedCondition(
28 const std::string & condition_name,
29 const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf),
33 robot_base_frame_(
"base_link")
35 getInput(
"global_frame", global_frame_);
36 getInput(
"robot_base_frame", robot_base_frame_);
51 return BT::NodeStatus::SUCCESS;
53 return BT::NodeStatus::FAILURE;
58 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
60 nav2_util::declare_parameter_if_not_declared(
61 node_,
"goal_reached_tol",
62 rclcpp::ParameterValue(0.25));
63 node_->get_parameter_or<
double>(
"goal_reached_tol", goal_reached_tol_, 0.25);
64 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
66 node_->get_parameter(
"transform_tolerance", transform_tolerance_);
73 geometry_msgs::msg::PoseStamped current_pose;
75 if (!nav2_util::getCurrentPose(
76 current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_))
78 RCLCPP_DEBUG(node_->get_logger(),
"Current robot pose is not available.");
82 geometry_msgs::msg::PoseStamped goal;
83 getInput(
"goal", goal);
84 double dx = goal.pose.position.x - current_pose.pose.position.x;
85 double dy = goal.pose.position.y - current_pose.pose.position.y;
87 return (dx * dx + dy * dy) <= (goal_reached_tol_ * goal_reached_tol_);
92 #include "behaviortree_cpp_v3/bt_factory.h"
93 BT_REGISTER_NODES(factory)
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise.
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.