Plane: fixed bungee launch

we need to not do the general purpose throttle suppression if in auto
takeoff
This commit is contained in:
Andrew Tridgell 2015-02-25 13:09:30 +11:00
parent e9bbe062f3
commit 98b583bccc
1 changed files with 13 additions and 5 deletions

View File

@ -596,16 +596,21 @@ static bool suppress_throttle(void)
}
if (control_mode==AUTO &&
auto_state.takeoff_complete == false &&
auto_takeoff_check()) {
// we're in auto takeoff
throttle_suppressed = false;
return false;
auto_state.takeoff_complete == false) {
if (auto_takeoff_check()) {
// we're in auto takeoff
throttle_suppressed = false;
return false;
}
// keep throttle suppressed
return true;
}
if (relative_altitude_abs_cm() >= 1000) {
// we're more than 10m from the home altitude
throttle_suppressed = false;
gcs_send_text_fmt(PSTR("Throttle unsuppressed - altitude %.2f"),
relative_altitude_abs_cm()*0.01f);
return false;
}
@ -616,6 +621,9 @@ static bool suppress_throttle(void)
// groundspeed with bad GPS reception
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
// we're moving at more than 5 m/s
gcs_send_text_fmt(PSTR("Throttle unsuppressed - speed %.2f airspeed %.2f"),
gps.ground_speed(),
airspeed.get_airspeed());
throttle_suppressed = false;
return false;
}