15 #include "nav2_behavior_tree/plugins/condition/initial_pose_received_condition.hpp"
17 namespace nav2_behavior_tree
20 BT::NodeStatus initialPoseReceived(BT::TreeNode &
tree_node)
22 auto initPoseReceived =
tree_node.config().blackboard->get<
bool>(
"initial_pose_received");
23 return initPoseReceived ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
28 #include "behaviortree_cpp_v3/bt_factory.h"
29 BT_REGISTER_NODES(factory)
31 factory.registerSimpleCondition(
32 "InitialPoseReceived",
33 std::bind(&nav2_behavior_tree::initialPoseReceived, std::placeholders::_1));