15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__TRANSFORM_AVAILABLE_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__TRANSFORM_AVAILABLE_CONDITION_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "behaviortree_cpp/condition_node.h"
24 #include "tf2_ros/buffer.h"
26 namespace nav2_behavior_tree
42 const std::string & condition_name,
43 const BT::NodeConfiguration & conf);
56 BT::NodeStatus
tick()
override;
70 BT::InputPort<std::string>(
"child", std::string(),
"Child frame for transform"),
71 BT::InputPort<std::string>(
"parent", std::string(),
"parent frame for transform")
76 rclcpp::Node::SharedPtr node_;
77 std::shared_ptr<tf2_ros::Buffer> tf_;
79 std::atomic<bool> was_found_;
81 std::string child_frame_;
82 std::string parent_frame_;