Browse Source

ArduCopter: Simplify boolean expression

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
zr-v5.1
Patrick José Pereira 4 years ago committed by Randy Mackay
parent
commit
ffe356d597
  1. 6
      ArduCopter/mode_throw.cpp
  2. 5
      ArduCopter/takeoff.cpp

6
ArduCopter/mode_throw.cpp

@ -269,11 +269,7 @@ bool ModeThrow::throw_detected() @@ -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()

5
ArduCopter/takeoff.cpp

@ -223,8 +223,5 @@ bool Mode::is_taking_off() const @@ -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();
}

Loading…
Cancel
Save