ArduPlane: set tailsitter VTOL pitch limits using only Q_ANGLE_MAX

This commit is contained in:
Mark Whitehorn 2017-05-09 22:45:18 -06:00 committed by Andrew Tridgell
parent 0e27d4bd6f
commit 65755454e0
1 changed files with 8 additions and 4 deletions

View File

@ -774,12 +774,16 @@ void Plane::update_flight_mode(void)
nav_roll_cd = (channel_roll->get_control_in() / 4500.0) * roll_limit;
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);
float pitch_input = channel_pitch->norm_input();
if (pitch_input > 0) {
nav_pitch_cd = pitch_input * MIN(aparm.pitch_limit_max_cd, quadplane.aparm.angle_max);
if (quadplane.is_tailsitter()) {
nav_pitch_cd = pitch_input * quadplane.aparm.angle_max;
} else {
nav_pitch_cd = pitch_input * MIN(-pitch_limit_min_cd, quadplane.aparm.angle_max);
if (pitch_input > 0) {
nav_pitch_cd = pitch_input * MIN(aparm.pitch_limit_max_cd, quadplane.aparm.angle_max);
} else {
nav_pitch_cd = pitch_input * MIN(-pitch_limit_min_cd, quadplane.aparm.angle_max);
}
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
}
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min_cd, aparm.pitch_limit_max_cd.get());
break;
}