20 #include "behaviortree_cpp/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),
35 goal_updater_topic_(
"goal_update"),
36 goals_updater_topic_(
"goals_update")
40 config().blackboard->template get<std::chrono::milliseconds>(
"bt_loop_duration");
43 void GoalUpdater::initialize()
45 createROSInterfaces();
48 void GoalUpdater::createROSInterfaces()
50 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
51 callback_group_ = node_->create_callback_group(
52 rclcpp::CallbackGroupType::MutuallyExclusive,
54 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
56 std::string goal_updater_topic_new;
57 std::string goals_updater_topic_new;
58 node_->get_parameter_or<std::string>(
"goal_updater_topic", goal_updater_topic_new,
"goal_update");
59 node_->get_parameter_or<std::string>(
"goals_updater_topic", goals_updater_topic_new,
63 if (goal_updater_topic_new != goal_updater_topic_ || !goal_sub_) {
64 goal_updater_topic_ = goal_updater_topic_new;
65 goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
67 std::bind(&GoalUpdater::callback_updated_goal,
this, _1),
71 if (goals_updater_topic_new != goals_updater_topic_ || !goals_sub_) {
72 goals_updater_topic_ = goals_updater_topic_new;
73 goals_sub_ = node_->create_subscription<nav_msgs::msg::Goals>(
75 std::bind(&GoalUpdater::callback_updated_goals,
this, _1),
81 inline BT::NodeStatus GoalUpdater::tick()
83 if (!BT::isStatusActive(status())) {
87 geometry_msgs::msg::PoseStamped goal;
88 nav_msgs::msg::Goals goals;
90 getInput(
"input_goal", goal);
91 getInput(
"input_goals", goals);
93 callback_group_executor_.spin_all(bt_loop_duration_);
95 if (last_goal_received_set_) {
96 if (last_goal_received_.header.stamp == rclcpp::Time(0)) {
99 node_->get_logger(),
"The received goal has no timestamp. Ignoring.");
100 setOutput(
"output_goal", goal);
102 auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
103 auto goal_time = rclcpp::Time(goal.header.stamp);
104 if (last_goal_received_time >= goal_time) {
105 setOutput(
"output_goal", last_goal_received_);
108 node_->get_logger(),
"The timestamp of the received goal (%f) is older than the "
109 "current goal (%f). Ignoring the received goal.",
110 last_goal_received_time.seconds(), goal_time.seconds());
111 setOutput(
"output_goal", goal);
115 setOutput(
"output_goal", goal);
118 if (last_goals_received_set_) {
119 if (last_goals_received_.goals.empty()) {
120 setOutput(
"output_goals", goals);
121 }
else if (last_goals_received_.header.stamp == rclcpp::Time(0)) {
123 node_->get_logger(),
"The received goals array has no timestamp. Ignoring.");
124 setOutput(
"output_goals", goals);
126 auto last_goals_received_time = rclcpp::Time(last_goals_received_.header.stamp);
127 auto goals_time = rclcpp::Time(goals.header.stamp);
128 if (last_goals_received_time >= goals_time) {
129 setOutput(
"output_goals", last_goals_received_);
132 node_->get_logger(),
"The timestamp of the received goals (%f) is older than the "
133 "current goals (%f). Ignoring the received goals.",
134 last_goals_received_time.seconds(), goals_time.seconds());
135 setOutput(
"output_goals", goals);
139 setOutput(
"output_goals", goals);
142 return child_node_->executeTick();
146 GoalUpdater::callback_updated_goal(
const geometry_msgs::msg::PoseStamped::SharedPtr msg)
148 last_goal_received_ = *msg;
149 last_goal_received_set_ =
true;
153 GoalUpdater::callback_updated_goals(
const nav_msgs::msg::Goals::SharedPtr msg)
155 last_goals_received_ = *msg;
156 last_goals_received_set_ =
true;
161 #include "behaviortree_cpp/bt_factory.h"
162 BT_REGISTER_NODES(factory)
A QoS profile for standard reliable topics with a history of 10 messages.
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.