19 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "behaviortree_cpp_v3/decorator_node.h"
22 #include "nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp"
24 #include "rclcpp/rclcpp.hpp"
26 namespace nav2_behavior_tree
29 using std::placeholders::_1;
32 const std::string & name,
33 const BT::NodeConfiguration & conf)
34 : BT::DecoratorNode(name, conf)
36 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
37 callback_group_ = node_->create_callback_group(
38 rclcpp::CallbackGroupType::MutuallyExclusive,
40 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
42 std::string goal_updater_topic;
43 node_->get_parameter_or<std::string>(
"goal_updater_topic", goal_updater_topic,
"goal_update");
45 rclcpp::SubscriptionOptions sub_option;
46 sub_option.callback_group = callback_group_;
47 goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
49 rclcpp::SystemDefaultsQoS(),
50 std::bind(&GoalUpdater::callback_updated_goal,
this, _1),
54 inline BT::NodeStatus GoalUpdater::tick()
56 geometry_msgs::msg::PoseStamped goal;
58 getInput(
"input_goal", goal);
60 callback_group_executor_.spin_some();
62 if (last_goal_received_.header.stamp != rclcpp::Time(0)) {
63 auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
64 auto goal_time = rclcpp::Time(goal.header.stamp);
65 if (last_goal_received_time > goal_time) {
66 goal = last_goal_received_;
69 node_->get_logger(),
"The timestamp of the received goal (%f) is older than the "
70 "current goal (%f). Ignoring the received goal.",
71 last_goal_received_time.seconds(), goal_time.seconds());
75 setOutput(
"output_goal", goal);
76 return child_node_->executeTick();
80 GoalUpdater::callback_updated_goal(
const geometry_msgs::msg::PoseStamped::SharedPtr msg)
82 last_goal_received_ = *msg;
87 #include "behaviortree_cpp_v3/bt_factory.h"
88 BT_REGISTER_NODES(factory)
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.