Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
are_poses_near_condition.hpp
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 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_POSES_NEAR_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_POSES_NEAR_CONDITION_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "nav2_ros_common/lifecycle_node.hpp"
22 #include "behaviortree_cpp/condition_node.h"
23 #include "tf2_ros/buffer.hpp"
24 #include "nav2_behavior_tree/bt_utils.hpp"
25 
26 namespace nav2_behavior_tree
27 {
28 
33 class ArePosesNearCondition : public BT::ConditionNode
34 {
35 public:
42  const std::string & condition_name,
43  const BT::NodeConfiguration & conf);
44 
48  ~ArePosesNearCondition() override = default;
49 
54  BT::NodeStatus tick() override;
55 
59  void initialize();
60 
65  bool arePosesNearby();
66 
71  static BT::PortsList providedPorts()
72  {
73  return {
74  BT::InputPort<geometry_msgs::msg::PoseStamped>("ref_pose", "Destination"),
75  BT::InputPort<geometry_msgs::msg::PoseStamped>("target_pose", "Destination"),
76  BT::InputPort<std::string>("global_frame", "Global frame"),
77  BT::InputPort<double>("tolerance", 0.5, "Tolerance")
78  };
79  }
80 
81 private:
82  nav2::LifecycleNode::SharedPtr node_;
83  std::shared_ptr<tf2_ros::Buffer> tf_;
84  double transform_tolerance_;
85  std::string global_frame_;
86 };
87 
88 } // namespace nav2_behavior_tree
89 
90 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_POSES_NEAR_CONDITION_HPP_
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.
static BT::PortsList providedPorts()
Creates list of BT ports.
void initialize()
Function to read parameters and initialize class variables.
~ArePosesNearCondition() override=default
A destructor for nav2_behavior_tree::ArePosesNearCondition.