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")
41 callback_group_executor_.spin_all(std::chrono::milliseconds(1));
44 void GoalUpdater::initialize()
46 createROSInterfaces();
49 void GoalUpdater::createROSInterfaces()
51 node_ = config().blackboard->get<rclcpp::Node::SharedPtr>(
"node");
52 callback_group_ = node_->create_callback_group(
53 rclcpp::CallbackGroupType::MutuallyExclusive,
55 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
57 std::string goal_updater_topic_new;
58 std::string goals_updater_topic_new;
59 node_->get_parameter_or<std::string>(
"goal_updater_topic", goal_updater_topic_new,
"goal_update");
60 node_->get_parameter_or<std::string>(
"goals_updater_topic", goals_updater_topic_new,
64 if (goal_updater_topic_new != goal_updater_topic_ || !goal_sub_) {
65 goal_updater_topic_ = goal_updater_topic_new;
66 rclcpp::SubscriptionOptions sub_option;
67 sub_option.callback_group = callback_group_;
68 goal_sub_ = node_->create_subscription<geometry_msgs::msg::PoseStamped>(
70 rclcpp::SystemDefaultsQoS(),
71 std::bind(&GoalUpdater::callback_updated_goal,
this, _1),
74 if (goals_updater_topic_new != goals_updater_topic_ || !goals_sub_) {
75 goals_updater_topic_ = goals_updater_topic_new;
76 rclcpp::SubscriptionOptions sub_option;
77 sub_option.callback_group = callback_group_;
78 goals_sub_ = node_->create_subscription<nav_msgs::msg::Goals>(
80 rclcpp::SystemDefaultsQoS(),
81 std::bind(&GoalUpdater::callback_updated_goals,
this, _1),
86 inline BT::NodeStatus GoalUpdater::tick()
88 if (!BT::isStatusActive(status())) {
92 geometry_msgs::msg::PoseStamped goal;
93 nav_msgs::msg::Goals goals;
95 getInput(
"input_goal", goal);
96 getInput(
"input_goals", goals);
98 callback_group_executor_.spin_all(std::chrono::milliseconds(49));
100 if (last_goal_received_set_) {
101 if (last_goal_received_.header.stamp == rclcpp::Time(0)) {
104 node_->get_logger(),
"The received goal has no timestamp. Ignoring.");
105 setOutput(
"output_goal", goal);
107 auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
108 auto goal_time = rclcpp::Time(goal.header.stamp);
109 if (last_goal_received_time >= goal_time) {
110 setOutput(
"output_goal", last_goal_received_);
113 node_->get_logger(),
"The timestamp of the received goal (%f) is older than the "
114 "current goal (%f). Ignoring the received goal.",
115 last_goal_received_time.seconds(), goal_time.seconds());
116 setOutput(
"output_goal", goal);
120 setOutput(
"output_goal", goal);
123 if (last_goals_received_set_) {
124 if (last_goals_received_.goals.empty()) {
125 setOutput(
"output_goals", goals);
126 }
else if (last_goals_received_.header.stamp == rclcpp::Time(0)) {
128 node_->get_logger(),
"The received goals array has no timestamp. Ignoring.");
129 setOutput(
"output_goals", goals);
131 auto last_goals_received_time = rclcpp::Time(last_goals_received_.header.stamp);
132 auto goals_time = rclcpp::Time(goals.header.stamp);
133 if (last_goals_received_time >= goals_time) {
134 setOutput(
"output_goals", last_goals_received_);
137 node_->get_logger(),
"The timestamp of the received goals (%f) is older than the "
138 "current goals (%f). Ignoring the received goals.",
139 last_goals_received_time.seconds(), goals_time.seconds());
140 setOutput(
"output_goals", goals);
144 setOutput(
"output_goals", goals);
147 return child_node_->executeTick();
151 GoalUpdater::callback_updated_goal(
const geometry_msgs::msg::PoseStamped::SharedPtr msg)
153 last_goal_received_ = *msg;
154 last_goal_received_set_ =
true;
158 GoalUpdater::callback_updated_goals(
const nav_msgs::msg::Goals::SharedPtr msg)
160 last_goals_received_ = *msg;
161 last_goals_received_set_ =
true;
166 #include "behaviortree_cpp/bt_factory.h"
167 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.