From 53db19a4d8cde77e623f404ebf2d6bc45d3ea7bb Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 9 Jun 2023 16:57:39 -0700 Subject: [PATCH] Fix merge conflict error (#3619) --- .../include/nav2_behavior_tree/bt_action_node.hpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index 5701c59d734..d7cd7f0b15c 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -47,7 +47,7 @@ class BtActionNode : public BT::ActionNodeBase const std::string & xml_tag_name, const std::string & action_name, const BT::NodeConfiguration & conf) - : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name) + : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true) { node_ = config().blackboard->template get("node"); callback_group_ = node_->create_callback_group( @@ -191,7 +191,10 @@ class BtActionNode : public BT::ActionNodeBase // setting the status to RUNNING to notify the BT Loggers (if any) setStatus(BT::NodeStatus::RUNNING); - // user defined callback + // reset the flag to send the goal or not, allowing the user the option to set it in on_tick + should_send_goal_ = true; + + // user defined callback, may modify "should_send_goal_". on_tick(); if (!should_send_goal_) { @@ -453,6 +456,9 @@ class BtActionNode : public BT::ActionNodeBase std::shared_ptr::SharedPtr>> future_goal_handle_; rclcpp::Time time_goal_sent_; + + // Can be set in on_tick or on_wait_for_result to indicate if a goal should be sent. + bool should_send_goal_; }; } // namespace nav2_behavior_tree