Plane: Quadaplane: add helper allow_forward_throttle_in_vtol_mode

This commit is contained in:
Iampete1 2023-12-22 16:07:45 +00:00 committed by Andrew Tridgell
parent 2e23fa7612
commit 3e955d12fa
3 changed files with 13 additions and 4 deletions

View File

@ -4742,4 +4742,10 @@ float QuadPlane::get_throttle_input() const
return ret;
}
// return true if forward throttle from forward_throttle_pct() should be used
bool QuadPlane::allow_forward_throttle_in_vtol_mode() const
{
return in_vtol_mode() && motors->armed() && (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN);
}
#endif // HAL_QUADPLANE_ENABLED

View File

@ -729,6 +729,11 @@ private:
*/
void setup_rp_fw_angle_gains(void);
/*
return true if forward throttle from forward_throttle_pct() should be used
*/
bool allow_forward_throttle_in_vtol_mode() const;
public:
void motor_test_output();
MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,

View File

@ -591,10 +591,8 @@ void Plane::set_throttle(void)
#if HAL_QUADPLANE_ENABLED
} else if (quadplane.in_vtol_mode()) {
float fwd_thr = 0;
// if armed and not spooled down ask quadplane code for forward throttle
if (quadplane.motors->armed() &&
quadplane.motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN) {
// if enabled ask quadplane code for forward throttle
if (quadplane.allow_forward_throttle_in_vtol_mode()) {
fwd_thr = constrain_float(quadplane.forward_throttle_pct(), min_throttle, max_throttle);
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr);