ArduPlane: add comments on tailsitter pitch limits

This commit is contained in:
Mark Whitehorn 2017-05-15 07:30:09 -06:00 committed by Andrew Tridgell
parent 65755454e0
commit 53b82d1d4d

View File

@ -774,9 +774,13 @@ 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();
// Scale from normalized input [-1,1] to centidegrees
if (quadplane.is_tailsitter()) {
// For tailsitters, the pitch range is symmetrical: [-Q_ANGLE_MAX,Q_ANGLE_MAX]
nav_pitch_cd = pitch_input * quadplane.aparm.angle_max;
} else {
// For non-tailsitters, pitch is further constrained by LIM_PITCH_MIN/MAX which may impose
// tighter (and asymmetrical) limits than Q_ANGLE_MAX
if (pitch_input > 0) {
nav_pitch_cd = pitch_input * MIN(aparm.pitch_limit_max_cd, quadplane.aparm.angle_max);
} else {