mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
Plane: Support seperate roll and pitch limits
This commit is contained in:
parent
7f5d6662b3
commit
124d18228b
@ -140,7 +140,8 @@ void QuadPlane::tailsitter_output(void)
|
|||||||
tilt_right = extra_elevator + tilt_right * tailsitter.vectored_hover_gain;
|
tilt_right = extra_elevator + tilt_right * tailsitter.vectored_hover_gain;
|
||||||
if (fabsf(tilt_left) >= SERVO_MAX || fabsf(tilt_right) >= SERVO_MAX) {
|
if (fabsf(tilt_left) >= SERVO_MAX || fabsf(tilt_right) >= SERVO_MAX) {
|
||||||
// prevent integrator windup
|
// prevent integrator windup
|
||||||
motors->limit.roll_pitch = 1;
|
motors->limit.roll = 1;
|
||||||
|
motors->limit.pitch = 1;
|
||||||
motors->limit.yaw = 1;
|
motors->limit.yaw = 1;
|
||||||
}
|
}
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, tilt_left);
|
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, tilt_left);
|
||||||
|
Loading…
Reference in New Issue
Block a user