15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GLOBALLY_UPDATED_GOAL_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__GLOBALLY_UPDATED_GOAL_CONDITION_HPP_
21 #include "rclcpp/rclcpp.hpp"
23 #include "behaviortree_cpp/condition_node.h"
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_behavior_tree/bt_utils.hpp"
28 namespace nav2_behavior_tree
43 const std::string & condition_name,
44 const BT::NodeConfiguration & conf);
52 BT::NodeStatus
tick()
override;
62 BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
63 "goals",
"Vector of navigation goals"),
64 BT::InputPort<geometry_msgs::msg::PoseStamped>(
65 "goal",
"Navigation goal"),
71 rclcpp::Node::SharedPtr node_;
72 geometry_msgs::msg::PoseStamped goal_;
73 std::vector<geometry_msgs::msg::PoseStamped> goals_;
A BT::ConditionNode that returns SUCCESS when goal is updated on the blackboard and FAILURE otherwise...
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus tick() override
The main override required by a BT action.