19 #include "nav2_behavior_tree/plugins/condition/transform_available_condition.hpp"
21 using namespace std::chrono_literals;
23 namespace nav2_behavior_tree
26 TransformAvailableCondition::TransformAvailableCondition(
27 const std::string & condition_name,
28 const BT::NodeConfiguration & conf)
29 : BT::ConditionNode(condition_name, conf),
32 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
33 tf_ = config().blackboard->get<std::shared_ptr<tf2_ros::Buffer>>(
"tf_buffer");
35 getInput(
"child", child_frame_);
36 getInput(
"parent", parent_frame_);
38 if (child_frame_.empty() || parent_frame_.empty()) {
40 node_->get_logger(),
"Child frame (%s) or parent frame (%s) were empty.",
41 child_frame_.c_str(), parent_frame_.c_str());
45 RCLCPP_DEBUG(node_->get_logger(),
"Initialized an TransformAvailableCondition BT node");
50 RCLCPP_DEBUG(node_->get_logger(),
"Shutting down TransformAvailableCondition BT node");
56 return BT::NodeStatus::SUCCESS;
60 bool found = tf_->canTransform(
61 child_frame_, parent_frame_, tf2::TimePointZero, &tf_error);
65 return BT::NodeStatus::SUCCESS;
69 node_->get_logger(),
"Transform from %s to %s was not found, tf error: %s",
70 child_frame_.c_str(), parent_frame_.c_str(), tf_error.c_str());
72 return BT::NodeStatus::FAILURE;
77 #include "behaviortree_cpp_v3/bt_factory.h"
78 BT_REGISTER_NODES(factory)