18 #include "nav2_util/robot_utils.hpp"
19 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "nav2_ros_common/node_utils.hpp"
22 #include "nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp"
24 namespace nav2_behavior_tree
28 const std::string & condition_name,
29 const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf)
32 auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
33 global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
34 node,
"global_frame",
this);
39 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
40 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
41 node_->get_parameter(
"transform_tolerance", transform_tolerance_);
46 if (!BT::isStatusActive(status())) {
51 return BT::NodeStatus::SUCCESS;
53 return BT::NodeStatus::FAILURE;
58 geometry_msgs::msg::PoseStamped pose1, pose2;
60 getInput(
"ref_pose", pose1);
61 getInput(
"target_pose", pose2);
62 getInput(
"tolerance", tol);
64 if (pose1.header.frame_id != pose2.header.frame_id) {
65 if (!nav2_util::transformPoseInTargetFrame(
66 pose1, pose1, *tf_, global_frame_, transform_tolerance_) ||
67 !nav2_util::transformPoseInTargetFrame(
68 pose2, pose2, *tf_, global_frame_, transform_tolerance_))
70 RCLCPP_ERROR(node_->get_logger(),
"Failed to transform poses to the same frame");
75 double dx = pose1.pose.position.x - pose2.pose.position.x;
76 double dy = pose1.pose.position.y - pose2.pose.position.y;
77 return (dx * dx + dy * dy) <= (tol * tol);
82 #include "behaviortree_cpp/bt_factory.h"
83 BT_REGISTER_NODES(factory)
A BT::ConditionNode that returns SUCCESS when a specified goal is reached and FAILURE otherwise.
ArePosesNearCondition(const std::string &condition_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::ArePosesNearCondition.
BT::NodeStatus tick() override
The main override required by a BT action.
bool arePosesNearby()
Checks if the current robot pose lies within a given distance from the goal.
void initialize()
Function to read parameters and initialize class variables.