mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: make TRAINING mode obey stall prevention roll limits
Fixes issue#2014
This commit is contained in:
parent
ac2e1552b2
commit
cc96f80f02
@ -552,6 +552,7 @@ void Plane::update_flight_mode(void)
|
||||
case TRAINING: {
|
||||
training_manual_roll = false;
|
||||
training_manual_pitch = false;
|
||||
update_load_factor();
|
||||
|
||||
// if the roll is past the set roll limit, then
|
||||
// we set target roll to the limit
|
||||
|
@ -1082,6 +1082,7 @@ void Plane::update_load_factor(void)
|
||||
// our airspeed is below the minimum airspeed. Limit roll to
|
||||
// 25 degrees
|
||||
nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500);
|
||||
roll_limit_cd = constrain_int32(roll_limit_cd, -2500, 2500);
|
||||
} else if (max_load_factor < aerodynamic_load_factor) {
|
||||
// the demanded nav_roll would take us past the aerodymamic
|
||||
// load limit. Limit our roll to a bank angle that will keep
|
||||
@ -1094,5 +1095,6 @@ void Plane::update_load_factor(void)
|
||||
roll_limit = 2500;
|
||||
}
|
||||
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);
|
||||
roll_limit_cd = constrain_int32(roll_limit_cd, -roll_limit, roll_limit);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user