17 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__GOAL_UPDATER_NODE_HPP_
18 #define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__GOAL_UPDATER_NODE_HPP_
23 #include "behaviortree_cpp/decorator_node.h"
24 #include "behaviortree_cpp/json_export.h"
25 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "nav_msgs/msg/goals.hpp"
27 #include "nav2_behavior_tree/bt_utils.hpp"
28 #include "nav2_behavior_tree/json_utils.hpp"
29 #include "rclcpp/rclcpp.hpp"
32 namespace nav2_behavior_tree
50 const std::string & xml_tag_name,
51 const BT::NodeConfiguration & conf);
60 BT::RegisterJsonDefinition<geometry_msgs::msg::PoseStamped>();
61 BT::RegisterJsonDefinition<nav_msgs::msg::Goals>();
64 BT::InputPort<geometry_msgs::msg::PoseStamped>(
"input_goal",
"Original Goal"),
65 BT::InputPort<nav_msgs::msg::Goals>(
"input_goals",
"Original Goals"),
66 BT::OutputPort<geometry_msgs::msg::PoseStamped>(
"output_goal",
67 "Received Goal by subscription"),
68 BT::OutputPort<nav_msgs::msg::Goals>(
"output_goals",
69 "Received Goals by subscription")
81 void createROSInterfaces();
86 BT::NodeStatus tick()
override;
92 void callback_updated_goal(
const geometry_msgs::msg::PoseStamped::SharedPtr msg);
98 void callback_updated_goals(
const nav_msgs::msg::Goals::SharedPtr msg);
100 nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;
101 nav2::Subscription<nav_msgs::msg::Goals>::SharedPtr goals_sub_;
103 geometry_msgs::msg::PoseStamped last_goal_received_;
104 bool last_goal_received_set_{
false};
105 nav_msgs::msg::Goals last_goals_received_;
106 bool last_goals_received_set_{
false};
108 nav2::LifecycleNode::SharedPtr node_;
109 rclcpp::CallbackGroup::SharedPtr callback_group_;
110 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
111 std::string goal_updater_topic_;
112 std::string goals_updater_topic_;
A BT::DecoratorNode that subscribes to a goal topic and updates the current goal on the blackboard.
GoalUpdater(const std::string &xml_tag_name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::GoalUpdater.
static BT::PortsList providedPorts()
Creates list of BT ports.