ArduCopter: Simplify boolean expression

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-03 11:04:38 -03:00 committed by Randy Mackay
parent 9bc8a8c912
commit ffe356d597
2 changed files with 2 additions and 9 deletions

View File

@ -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)); 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 // start motors and enter the control mode if we are in continuous freefall
if (throw_condition_confirmed) { return throw_condition_confirmed;
return true;
} else {
return false;
}
} }
bool ModeThrow::throw_attitude_good() bool ModeThrow::throw_attitude_good()

View File

@ -223,8 +223,5 @@ bool Mode::is_taking_off() const
if (copter.ap.land_complete) { if (copter.ap.land_complete) {
return false; return false;
} }
if (takeoff.running()) { return takeoff.running();
return true;
}
return false;
} }