Plane: added Q_TAILSIT_THSCMX

this provides more flexibility in tailsitter throttle scaling
This commit is contained in:
IamPete1 2018-04-15 12:31:53 +01:00 committed by Andrew Tridgell
parent c8ce76e8a6
commit 20c67019b0
3 changed files with 13 additions and 4 deletions

View File

@ -352,6 +352,13 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
AP_SUBGROUPPTR(loiter_nav, "LOIT_", 2, QuadPlane, AC_Loiter),
// @Param: TAILSIT_THSCMX
// @DisplayName: Maximum control throttle scaling value
// @Description: Maximum value of throttle scaling for tailsitter velocity scaling, reduce this value to remove low thorottle D ossilaitons
// @Range: 1 5
// @User: Standard
AP_GROUPINFO("TAILSIT_THSCMX", 3, QuadPlane, tailsitter.throttle_scale_max, 5),
AP_GROUPEND
};

View File

@ -401,6 +401,7 @@ private:
AP_Float vectored_forward_gain;
AP_Float vectored_hover_gain;
AP_Float vectored_hover_power;
AP_Float throttle_scale_max;
} tailsitter;
// the attitude view of the VTOL attitude controller

View File

@ -209,13 +209,14 @@ void QuadPlane::tailsitter_speed_scaling(void)
{
const float hover_throttle = motors->get_throttle_hover();
const float throttle = motors->get_throttle();
const float scaling_max = 5;
float scaling = 1;
float scaling;
if (is_zero(throttle)) {
scaling = scaling_max;
scaling = tailsitter.throttle_scale_max;
} else {
scaling = constrain_float(hover_throttle / throttle, 1/scaling_max, scaling_max);
scaling = constrain_float(hover_throttle / throttle, 0, tailsitter.throttle_scale_max);
}
const SRV_Channel::Aux_servo_function_t functions[2] = {
SRV_Channel::Aux_servo_function_t::k_aileron,
SRV_Channel::Aux_servo_function_t::k_elevator};