diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ad2c4f77ff..db45e9d6ae 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -370,10 +370,15 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { AP_GROUPEND }; -static const struct { +struct defaults_struct { const char *name; float value; -} defaults_table[] = { +}; + +/* + defaults for all quadplanes + */ +static const struct defaults_struct defaults_table[] = { { "Q_A_RAT_RLL_P", 0.25 }, { "Q_A_RAT_RLL_I", 0.25 }, { "Q_A_RAT_RLL_FILT", 10.0 }, @@ -383,6 +388,19 @@ static const struct { { "Q_M_SPOOL_TIME", 0.25 }, }; +/* + extra defaults for tailsitters + */ +static const struct defaults_struct defaults_table_tailsitter[] = { + { "KFF_RDDRMIX", 0.02 }, + { "Q_A_RAT_PIT_FF", 0.2 }, + { "Q_A_RAT_YAW_FF", 0.2 }, + { "Q_A_RAT_YAW_I", 0.18 }, + { "LIM_PITCH_MAX", 3000 }, + { "LIM_PITCH_MIN", -3000 }, + { "MIXING_GAIN", 1.0 }, +}; + QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) : ahrs(_ahrs) { @@ -567,19 +585,33 @@ failed: return false; } +/* + setup default parameters from a defaults_struct table + */ +void QuadPlane::setup_defaults_table(const struct defaults_struct *table, uint8_t count) +{ + for (uint8_t i=0; i