15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_POSES_NEAR_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__ARE_POSES_NEAR_CONDITION_HPP_
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"
26 namespace nav2_behavior_tree
42 const std::string & condition_name,
43 const BT::NodeConfiguration & conf);
54 BT::NodeStatus
tick()
override;
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")
82 nav2::LifecycleNode::SharedPtr node_;
83 std::shared_ptr<tf2_ros::Buffer> tf_;
84 double transform_tolerance_;
85 std::string global_frame_;
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.