diff --git a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp index c20708788c..4127bc6843 100644 --- a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp +++ b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp @@ -57,7 +57,9 @@ inline BT::NodeStatus GoalUpdater::tick() getInput("input_goal", goal); - callback_group_executor_.spin_all(std::chrono::milliseconds(50)); + // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin + callback_group_executor_.spin_all(std::chrono::milliseconds(1)); + callback_group_executor_.spin_all(std::chrono::milliseconds(49)); if (last_goal_received_.header.stamp != rclcpp::Time(0)) { auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);