Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,6 @@ ControllerSelector::ControllerSelector(
: BT::SyncActionNode(name, conf)
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
}

void ControllerSelector::initialize()
Expand Down Expand Up @@ -69,7 +66,7 @@ BT::NodeStatus ControllerSelector::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

// This behavior always use the last selected controller received from the topic input.
// When no input is specified it uses the default controller.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ BT::NodeStatus GoalCheckerSelector::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

// This behavior always use the last selected goal checker received from the topic input.
// When no input is specified it uses the default goal checker.
Expand Down
5 changes: 1 addition & 4 deletions nav2_behavior_tree/plugins/action/planner_selector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,6 @@ PlannerSelector::PlannerSelector(
: BT::SyncActionNode(name, conf)
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
}

void PlannerSelector::initialize()
Expand Down Expand Up @@ -69,7 +66,7 @@ BT::NodeStatus PlannerSelector::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

// This behavior always use the last selected planner received from the topic input.
// When no input is specified it uses the default planner.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ BT::NodeStatus ProgressCheckerSelector::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

// This behavior always use the last selected progress checker received from the topic input.
// When no input is specified it uses the default goaprogressl checker.
Expand Down
5 changes: 1 addition & 4 deletions nav2_behavior_tree/plugins/action/smoother_selector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,6 @@ SmootherSelector::SmootherSelector(
: BT::SyncActionNode(name, conf)
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
}

void SmootherSelector::initialize()
Expand Down Expand Up @@ -70,7 +67,7 @@ BT::NodeStatus SmootherSelector::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

// This behavior always use the last selected smoother received from the topic input.
// When no input is specified it uses the default smoother.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,6 @@ IsBatteryChargingCondition::IsBatteryChargingCondition(
is_battery_charging_(false)
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
}

void IsBatteryChargingCondition::initialize()
Expand Down Expand Up @@ -65,7 +62,7 @@ BT::NodeStatus IsBatteryChargingCondition::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
if (is_battery_charging_) {
return BT::NodeStatus::SUCCESS;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@ IsBatteryLowCondition::IsBatteryLowCondition(
is_battery_low_(false)
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
}

void IsBatteryLowCondition::initialize()
Expand Down Expand Up @@ -71,7 +68,7 @@ BT::NodeStatus IsBatteryLowCondition::tick()
initialize();
}

callback_group_executor_.spin_some();
callback_group_executor_.spin_all(std::chrono::milliseconds(50));
if (is_battery_low_) {
return BT::NodeStatus::SUCCESS;
}
Expand Down
5 changes: 1 addition & 4 deletions nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,6 @@ GoalUpdater::GoalUpdater(
goals_updater_topic_("goals_update")
{
initialize();

// Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
callback_group_executor_.spin_all(std::chrono::milliseconds(1));
}

void GoalUpdater::initialize()
Expand Down Expand Up @@ -91,7 +88,7 @@ inline BT::NodeStatus GoalUpdater::tick()
getInput("input_goal", goal);
getInput("input_goals", goals);

callback_group_executor_.spin_all(std::chrono::milliseconds(49));
callback_group_executor_.spin_all(std::chrono::milliseconds(50));

if (last_goal_received_set_) {
if (last_goal_received_.header.stamp == rclcpp::Time(0)) {
Expand Down
1 change: 0 additions & 1 deletion nav2_route/test/test_graph_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,6 @@ TEST(GraphLoader, test_transformation_api)
tf_broadcaster->sendTransform(transform);
rclcpp::Rate(1).sleep();
tf_broadcaster->sendTransform(transform);
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(1));
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(50));

graph[0].coords.frame_id = "map_test";
Expand Down
1 change: 0 additions & 1 deletion nav2_route/test/test_graph_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,6 @@ TEST(GraphSaver, test_transformation_api)
tf_broadcaster->sendTransform(transform);
rclcpp::Rate(1).sleep();
tf_broadcaster->sendTransform(transform);
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(1));
rclcpp::spin_all(node->get_node_base_interface(), std::chrono::milliseconds(50));

GraphSaver graph_saver(node, tf, frame);
Expand Down
Loading