mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: fixed auto-takeoff throttle trigger for inverted launch
quite an unusual setup, but has been done :-)
This commit is contained in:
parent
787a2093ec
commit
287614b415
@ -61,7 +61,7 @@ bool Plane::auto_takeoff_check(void)
|
||||
// Check aircraft attitude for bad launch
|
||||
if (ahrs.pitch_sensor <= -3000 ||
|
||||
ahrs.pitch_sensor >= 4500 ||
|
||||
labs(ahrs.roll_sensor) > 3000) {
|
||||
(!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
|
||||
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad launch AUTO");
|
||||
goto no_launch;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user