diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 39dbaa0cf4..47012cbb35 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1209,6 +1209,28 @@ void Copter::convert_pid_parameters(void) AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table)); #endif + // attitude control filter parameter changes (from _FILT to FLTE or FLTD) for Copter-3.7 + const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = { +#if FRAME_CONFIG == HELI_FRAME + // tradheli moves ATC_RAT_RLL/PIT_FILT to FLTE, ATC_RAT_YAW_FILT to FLTE + { Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" }, + { Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" }, + { Parameters::k_param_attitude_control, 388, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" }, +#else + // multicopters move ATC_RAT_RLL/PIT_FILT to FLTD, ATC_RAT_YAW_FILT to FLTE + { Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTD" }, + { Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTD" }, + { Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" }, + { Parameters::k_param_attitude_control, 449, AP_PARAM_FLOAT, "ATC_RAT_RLL_FF" }, + { Parameters::k_param_attitude_control, 450, AP_PARAM_FLOAT, "ATC_RAT_PIT_FF" }, + { Parameters::k_param_attitude_control, 451, AP_PARAM_FLOAT, "ATC_RAT_YAW_FF" }, +#endif + }; + uint8_t filt_table_size = ARRAY_SIZE(ff_and_filt_conversion_info); + for (uint8_t i=0; iget_rate_yaw_pid().kI().set_default(0.015); break; case AP_Motors::MOTOR_FRAME_TRI: - attitude_control->get_rate_yaw_pid().filt_hz().set_default(100); + attitude_control->get_rate_yaw_pid().filt_D_hz().set_default(100); break; default: break; diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index bb1c3d06b8..09bfede5ad 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -215,7 +215,7 @@ void Copter::tuning() #endif case TUNING_RATE_YAW_FILT: - attitude_control->get_rate_yaw_pid().filt_hz(tuning_value); + attitude_control->get_rate_yaw_pid().filt_E_hz(tuning_value); break; #if WINCH_ENABLED == ENABLED