From ffe356d59704ef50376e9bc6b1229498d6c7a55e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Wed, 3 Feb 2021 11:04:38 -0300 Subject: [PATCH] ArduCopter: Simplify boolean expression MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- ArduCopter/mode_throw.cpp | 6 +----- ArduCopter/takeoff.cpp | 5 +---- 2 files changed, 2 insertions(+), 9 deletions(-) diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index 224b38bc27..af7b3ca7c8 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -269,11 +269,7 @@ bool ModeThrow::throw_detected() bool throw_condition_confirmed = ((AP_HAL::millis() - free_fall_start_ms < 500) && ((inertial_nav.get_velocity().z - free_fall_start_velz) < -250.0f)); // start motors and enter the control mode if we are in continuous freefall - if (throw_condition_confirmed) { - return true; - } else { - return false; - } + return throw_condition_confirmed; } bool ModeThrow::throw_attitude_good() diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index ae6a73f08a..7175c14591 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -223,8 +223,5 @@ bool Mode::is_taking_off() const if (copter.ap.land_complete) { return false; } - if (takeoff.running()) { - return true; - } - return false; + return takeoff.running(); }