Rover: param conversions for FF and FILT params

This commit is contained in:
Randy Mackay 2019-07-15 20:54:44 +09:00
parent 34da437266
commit 35a57d1156
1 changed files with 16 additions and 0 deletions

View File

@ -826,6 +826,22 @@ void Rover::load_parameters(void)
AP_Param::convert_old_parameter(&cruise_speed_info, 1.0f);
}
// attitude control FF and FILT parameter changes for Rover-3.6
const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = {
{ Parameters::k_param_g2, 24650, AP_PARAM_FLOAT, "ATC_STR_RAT_FLTE" },
{ Parameters::k_param_g2, 28746, AP_PARAM_FLOAT, "ATC_STR_RAT_FF" },
{ Parameters::k_param_g2, 24714, AP_PARAM_FLOAT, "ATC_SPEED_FLTE" },
{ Parameters::k_param_g2, 28810, AP_PARAM_FLOAT, "ATC_SPEED_FF" },
{ Parameters::k_param_g2, 25226, AP_PARAM_FLOAT, "ATC_BAL_FLTE" },
{ Parameters::k_param_g2, 29322, AP_PARAM_FLOAT, "ATC_BAL_FF" },
{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },
{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },
};
uint8_t filt_table_size = ARRAY_SIZE(ff_and_filt_conversion_info);
for (uint8_t i=0; i<filt_table_size; i++) {
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[i], 1.0f);
}
// configure safety switch to allow stopping the motors while armed
#if HAL_HAVE_SAFETY_SWITCH
AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|