Browse Source

Plane: allow tailsitters to takeoff with any attitude

master
Andrew Tridgell 8 years ago
parent
commit
4e4f5a7ac9
  1. 14
      ArduPlane/takeoff.cpp

14
ArduPlane/takeoff.cpp

@ -58,12 +58,14 @@ bool Plane::auto_takeoff_check(void)
goto no_launch; goto no_launch;
} }
// Check aircraft attitude for bad launch if (!is_tailsitter()) {
if (ahrs.pitch_sensor <= -3000 || // Check aircraft attitude for bad launch
ahrs.pitch_sensor >= 4500 || if (ahrs.pitch_sensor <= -3000 ||
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) { ahrs.pitch_sensor >= 4500 ||
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad launch AUTO"); (!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
goto no_launch; gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad launch AUTO");
goto no_launch;
}
} }
// Check ground speed and time delay // Check ground speed and time delay

Loading…
Cancel
Save