From 53b82d1d4d3a37cb04fb0fb68902e1e0dcd0a6a8 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Mon, 15 May 2017 07:30:09 -0600 Subject: [PATCH] ArduPlane: add comments on tailsitter pitch limits --- ArduPlane/ArduPlane.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 8e4b140f50..874e1abf14 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -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 {