mirror of https://github.com/ArduPilot/ardupilot
Sub: param conversion for attitude control FF and FILT
This commit is contained in:
parent
35a57d1156
commit
ad4b6fdeae
|
@ -705,6 +705,18 @@ void Sub::load_parameters()
|
|||
|
||||
void Sub::convert_old_parameters()
|
||||
{
|
||||
// attitude control filter parameter changes from _FILT to FLTE or FLTD
|
||||
const AP_Param::ConversionInfo filt_conversion_info[] = {
|
||||
// move ATC_RAT_RLL/PIT_FILT to FLTD, move ATC_RAT_YAW_FILT to FLTE
|
||||
{ Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" },
|
||||
{ Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" },
|
||||
{ Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" },
|
||||
};
|
||||
uint8_t filt_table_size = ARRAY_SIZE(filt_conversion_info);
|
||||
for (uint8_t i=0; i<filt_table_size; i++) {
|
||||
AP_Param::convert_old_parameters(&filt_conversion_info[i], 1.0f);
|
||||
}
|
||||
|
||||
const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old,
|
||||
Parameters::k_param_rc_3_old, Parameters::k_param_rc_4_old,
|
||||
Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old,
|
||||
|
|
Loading…
Reference in New Issue