Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
are_poses_near_condition.cpp
1 // Copyright (c) 2025 Open Navigation LLC
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 #include <string>
16 #include <memory>
17 
18 #include "nav2_util/robot_utils.hpp"
19 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "nav2_ros_common/node_utils.hpp"
21 
22 #include "nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp"
23 
24 namespace nav2_behavior_tree
25 {
26 
28  const std::string & condition_name,
29  const BT::NodeConfiguration & conf)
30 : BT::ConditionNode(condition_name, conf)
31 {
32  auto node = config().blackboard->get<nav2::LifecycleNode::SharedPtr>("node");
33  global_frame_ = BT::deconflictPortAndParamFrame<std::string>(
34  node, "global_frame", this);
35 }
36 
38 {
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_);
42 }
43 
45 {
46  if (!BT::isStatusActive(status())) {
47  initialize();
48  }
49 
50  if (arePosesNearby()) {
51  return BT::NodeStatus::SUCCESS;
52  }
53  return BT::NodeStatus::FAILURE;
54 }
55 
57 {
58  geometry_msgs::msg::PoseStamped pose1, pose2;
59  double tol;
60  getInput("ref_pose", pose1);
61  getInput("target_pose", pose2);
62  getInput("tolerance", tol);
63 
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_))
69  {
70  RCLCPP_ERROR(node_->get_logger(), "Failed to transform poses to the same frame");
71  return false;
72  }
73  }
74 
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);
78 }
79 
80 } // namespace nav2_behavior_tree
81 
82 #include "behaviortree_cpp/bt_factory.h"
83 BT_REGISTER_NODES(factory)
84 {
85  factory.registerNodeType<nav2_behavior_tree::ArePosesNearCondition>("ArePosesNear");
86 }
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.