Plane: fixed a sign error in the angle assist code
thanks to Leonard for finding this!
This commit is contained in:
parent
41d999994a
commit
d5ec7b0aad
@ -1101,7 +1101,7 @@ bool QuadPlane::assistance_needed(float aspeed)
|
||||
const uint16_t allowed_envelope_error_cd = 500U;
|
||||
if (labs(ahrs.roll_sensor) <= plane.aparm.roll_limit_cd+allowed_envelope_error_cd &&
|
||||
ahrs.pitch_sensor < plane.aparm.pitch_limit_max_cd+allowed_envelope_error_cd &&
|
||||
ahrs.pitch_sensor > -(plane.aparm.pitch_limit_min_cd+allowed_envelope_error_cd)) {
|
||||
ahrs.pitch_sensor > -(allowed_envelope_error_cd-plane.aparm.pitch_limit_min_cd)) {
|
||||
// we are inside allowed attitude envelope
|
||||
in_angle_assist = false;
|
||||
angle_error_start_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user