From f6246a3c22f1c5636ac9f7aa8276bfef8c4f36ec Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 4 May 2024 07:45:07 +0900 Subject: [PATCH] Rover: Delete unnecessary decisions --- Rover/sailboat.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index 7fb957e06c..24b11dea09 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -275,9 +275,9 @@ void Sailboat::relax_sails() // calculate throttle and mainsail angle required to attain desired speed (in m/s) void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttle_out) { + throttle_out = 0.0f; if (!sail_enabled()) { relax_sails(); - throttle_out = 0.0f; return; } @@ -292,8 +292,6 @@ void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttl rover.g.speed_cruise, rover.g.throttle_cruise * 0.01f, rover.G_Dt); - } else { - throttle_out = 0.0f; } if (motor_state == UseMotor::USE_MOTOR_ALWAYS) {