Skip to content

Commit 12dccee

Browse files
committed
Update spin some to use spin all
Signed-off-by: mini-1235 <[email protected]>
1 parent 7990415 commit 12dccee

File tree

10 files changed

+8
-12
lines changed

10 files changed

+8
-12
lines changed

nav2_behavior_tree/plugins/action/controller_selector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ BT::NodeStatus ControllerSelector::tick()
6666
initialize();
6767
}
6868

69-
callback_group_executor_.spin_some();
69+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
7070

7171
// This behavior always use the last selected controller received from the topic input.
7272
// When no input is specified it uses the default controller.

nav2_behavior_tree/plugins/action/goal_checker_selector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ BT::NodeStatus GoalCheckerSelector::tick()
6666
initialize();
6767
}
6868

69-
callback_group_executor_.spin_some();
69+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
7070

7171
// This behavior always use the last selected goal checker received from the topic input.
7272
// When no input is specified it uses the default goal checker.

nav2_behavior_tree/plugins/action/planner_selector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ BT::NodeStatus PlannerSelector::tick()
6666
initialize();
6767
}
6868

69-
callback_group_executor_.spin_some();
69+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
7070

7171
// This behavior always use the last selected planner received from the topic input.
7272
// When no input is specified it uses the default planner.

nav2_behavior_tree/plugins/action/progress_checker_selector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ BT::NodeStatus ProgressCheckerSelector::tick()
6565
initialize();
6666
}
6767

68-
callback_group_executor_.spin_some();
68+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
6969

7070
// This behavior always use the last selected progress checker received from the topic input.
7171
// When no input is specified it uses the default goaprogressl checker.

nav2_behavior_tree/plugins/action/smoother_selector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ BT::NodeStatus SmootherSelector::tick()
6767
initialize();
6868
}
6969

70-
callback_group_executor_.spin_some();
70+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
7171

7272
// This behavior always use the last selected smoother received from the topic input.
7373
// When no input is specified it uses the default smoother.

nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ BT::NodeStatus IsBatteryChargingCondition::tick()
6262
initialize();
6363
}
6464

65-
callback_group_executor_.spin_some();
65+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
6666
if (is_battery_charging_) {
6767
return BT::NodeStatus::SUCCESS;
6868
}

nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ BT::NodeStatus IsBatteryLowCondition::tick()
6868
initialize();
6969
}
7070

71-
callback_group_executor_.spin_some();
71+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
7272
if (is_battery_low_) {
7373
return BT::NodeStatus::SUCCESS;
7474
}

nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,9 +88,7 @@ inline BT::NodeStatus GoalUpdater::tick()
8888
getInput("input_goal", goal);
8989
getInput("input_goals", goals);
9090

91-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
92-
callback_group_executor_.spin_all(std::chrono::milliseconds(1));
93-
callback_group_executor_.spin_all(std::chrono::milliseconds(49));
91+
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
9492

9593
if (last_goal_received_set_) {
9694
if (last_goal_received_.header.stamp == rclcpp::Time(0)) {

nav2_route/test/test_graph_loader.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,6 @@ TEST(GraphLoader, test_transformation_api)
107107
tf_broadcaster->sendTransform(transform);
108108
rclcpp::Rate(1).sleep();
109109
tf_broadcaster->sendTransform(transform);
110-
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(1));
111110
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(50));
112111

113112
graph[0].coords.frame_id = "map_test";

nav2_route/test/test_graph_saver.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -143,7 +143,6 @@ TEST(GraphSaver, test_transformation_api)
143143
tf_broadcaster->sendTransform(transform);
144144
rclcpp::Rate(1).sleep();
145145
tf_broadcaster->sendTransform(transform);
146-
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(1));
147146
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(50));
148147

149148
GraphSaver graph_saver(node, tf, frame);

0 commit comments

Comments
 (0)