We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent 359c744 commit 44896e9Copy full SHA for 44896e9
nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp
@@ -57,7 +57,9 @@ inline BT::NodeStatus GoalUpdater::tick()
57
58
getInput("input_goal", goal);
59
60
- callback_group_executor_.spin_all(std::chrono::milliseconds(50));
+ // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
61
+ callback_group_executor_.spin_all(std::chrono::milliseconds(1));
62
+ callback_group_executor_.spin_all(std::chrono::milliseconds(49));
63
64
if (last_goal_received_.header.stamp != rclcpp::Time(0)) {
65
auto last_goal_received_time = rclcpp::Time(last_goal_received_.header.stamp);
0 commit comments