mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
ArduPlane: change is_tailsitter() to tailsitter_active()
This commit is contained in:
parent
53b82d1d4d
commit
6607dafc66
@ -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 {
|
||||
|
Loading…
Reference in New Issue
Block a user