Skip to content

Commit 7990415

Browse files
committed
Revert "Add double spin_some in some BT nodes (#5055)"
This reverts commit 4e8469e. Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
1 parent 16acda8 commit 7990415

File tree

6 files changed

+2
-18
lines changed

6 files changed

+2
-18
lines changed

nav2_behavior_tree/plugins/action/controller_selector_node.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,6 @@ ControllerSelector::ControllerSelector(
3333
: BT::SyncActionNode(name, conf)
3434
{
3535
initialize();
36-
37-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
38-
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
3936
}
4037

4138
void ControllerSelector::initialize()

nav2_behavior_tree/plugins/action/planner_selector_node.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,6 @@ PlannerSelector::PlannerSelector(
3333
: BT::SyncActionNode(name, conf)
3434
{
3535
initialize();
36-
37-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
38-
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
3936
}
4037

4138
void PlannerSelector::initialize()

nav2_behavior_tree/plugins/action/smoother_selector_node.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,6 @@ SmootherSelector::SmootherSelector(
3434
: BT::SyncActionNode(name, conf)
3535
{
3636
initialize();
37-
38-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
39-
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
4037
}
4138

4239
void SmootherSelector::initialize()

nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,6 @@ IsBatteryChargingCondition::IsBatteryChargingCondition(
2727
is_battery_charging_(false)
2828
{
2929
initialize();
30-
31-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
32-
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
3330
}
3431

3532
void IsBatteryChargingCondition::initialize()

nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,6 @@ IsBatteryLowCondition::IsBatteryLowCondition(
3030
is_battery_low_(false)
3131
{
3232
initialize();
33-
34-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
35-
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
3633
}
3734

3835
void IsBatteryLowCondition::initialize()

nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,6 @@ GoalUpdater::GoalUpdater(
3636
goals_updater_topic_("goals_update")
3737
{
3838
initialize();
39-
40-
// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
41-
callback_group_executor_.spin_all(std::chrono::milliseconds(1));
4239
}
4340

4441
void GoalUpdater::initialize()
@@ -91,6 +88,8 @@ inline BT::NodeStatus GoalUpdater::tick()
9188
getInput("input_goal", goal);
9289
getInput("input_goals", goals);
9390

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));
9493
callback_group_executor_.spin_all(std::chrono::milliseconds(49));
9594

9695
if (last_goal_received_set_) {

0 commit comments

Comments
 (0)