18 #include "nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp"
20 namespace nav2_behavior_tree
23 GloballyUpdatedGoalCondition::GloballyUpdatedGoalCondition(
24 const std::string & condition_name,
25 const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
29 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
36 BT::getInputOrBlackboard(
"goals", goals_);
37 BT::getInputOrBlackboard(
"goal", goal_);
38 return BT::NodeStatus::SUCCESS;
41 nav_msgs::msg::Goals current_goals;
42 BT::getInputOrBlackboard(
"goals", current_goals);
43 geometry_msgs::msg::PoseStamped current_goal;
44 BT::getInputOrBlackboard(
"goal", current_goal);
46 if (goal_ != current_goal || goals_ != current_goals) {
48 goals_ = current_goals;
49 return BT::NodeStatus::SUCCESS;
52 return BT::NodeStatus::FAILURE;
57 #include "behaviortree_cpp/bt_factory.h"
58 BT_REGISTER_NODES(factory)
A BT::ConditionNode that returns SUCCESS when goal is updated on the blackboard and FAILURE otherwise...
BT::NodeStatus tick() override
The main override required by a BT action.