From 6607dafc66b7fc8a9ef8e91046cc8a5f43443b26 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Mon, 15 May 2017 20:42:18 -0600 Subject: [PATCH] ArduPlane: change is_tailsitter() to tailsitter_active() --- ArduPlane/ArduPlane.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 874e1abf14..18e03fdba3 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -775,12 +775,12 @@ void Plane::update_flight_mode(void) 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()) { + if (quadplane.tailsitter_active()) { // 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 + // pitch is further constrained by LIM_PITCH_MIN/MAX which may impose + // tighter (possibly 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 {