Plane: fix bug in tilt position for QLOITER and QRTL if THR_MIN !=0

This commit is contained in:
Hwurzburg 2021-06-28 12:43:50 -05:00 committed by Andrew Tridgell
parent 4f7da5867d
commit 8310f4a718
1 changed files with 2 additions and 3 deletions

View File

@ -144,7 +144,7 @@ void QuadPlane::tiltrotor_continuous_update(void)
// Q_TILT_MAX. Anything above 50% throttle gets // Q_TILT_MAX. Anything above 50% throttle gets
// Q_TILT_MAX. Below 50% throttle we decrease linearly. This // Q_TILT_MAX. Below 50% throttle we decrease linearly. This
// relies heavily on Q_VFWD_GAIN being set appropriately. // relies heavily on Q_VFWD_GAIN being set appropriately.
float settilt = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 50.0f, 0, 1); float settilt = constrain_float((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0)) / 50.0f, 0, 1);
tiltrotor_slew(settilt * tilt.max_angle_deg / 90.0f); tiltrotor_slew(settilt * tilt.max_angle_deg / 90.0f);
} }
} }
@ -346,7 +346,6 @@ void QuadPlane::tiltrotor_vectoring(void)
// calculate the basic tilt amount from current_tilt // calculate the basic tilt amount from current_tilt
float base_output = zero_out + (tilt.current_tilt * (level_out - zero_out)); float base_output = zero_out + (tilt.current_tilt * (level_out - zero_out));
// for testing when disarmed, apply vectored yaw in proportion to rudder stick // for testing when disarmed, apply vectored yaw in proportion to rudder stick
// Wait TILT_DELAY_MS after disarming to allow props to spin down first. // Wait TILT_DELAY_MS after disarming to allow props to spin down first.
constexpr uint32_t TILT_DELAY_MS = 3000; constexpr uint32_t TILT_DELAY_MS = 3000;