mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Plane: auto-invert pitch control when upside down
this helps to recover when flying inverted, for example when in manual and hitting the lower altitude geofence
This commit is contained in:
parent
7af3c667a5
commit
11ad9d5a2d
@ -105,18 +105,19 @@ static void stabilize_pitch(float speed_scaler)
|
||||
g.flybywire_airspeed_min, g.flybywire_airspeed_max);
|
||||
break;
|
||||
|
||||
default:
|
||||
default: {
|
||||
int32_t tempcalc = nav_pitch_cd +
|
||||
fabsf(ahrs.roll_sensor * g.kff_pitch_compensation) +
|
||||
(g.channel_throttle.servo_out * g.kff_throttle_to_pitch) -
|
||||
(ahrs.pitch_sensor - g.pitch_trim_cd);
|
||||
if (inverted_flight) {
|
||||
if (abs(ahrs.roll_sensor) > 9000) {
|
||||
// when flying upside down the elevator control is inverted
|
||||
tempcalc = -tempcalc;
|
||||
}
|
||||
g.channel_pitch.servo_out = g.pidServoPitch.get_pid_4500(tempcalc, speed_scaler);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user