Copter: support for upgrade to PID object

This commit is contained in:
Leonard Hall 2019-06-27 19:06:47 +09:30 committed by Randy Mackay
parent d61aa7a4ce
commit f128e93ec5
3 changed files with 24 additions and 2 deletions

View File

@ -1209,6 +1209,28 @@ void Copter::convert_pid_parameters(void)
AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table)); AP_Param::set_defaults_from_table(heli_defaults_table, ARRAY_SIZE(heli_defaults_table));
#endif #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; i<filt_table_size; i++) {
AP_Param::convert_old_parameters(&ff_and_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, 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_3_old, Parameters::k_param_rc_4_old,
Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old, Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old,

View File

@ -580,7 +580,7 @@ void Copter::allocate_motors(void)
attitude_control->get_rate_yaw_pid().kI().set_default(0.015); attitude_control->get_rate_yaw_pid().kI().set_default(0.015);
break; break;
case AP_Motors::MOTOR_FRAME_TRI: 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; break;
default: default:
break; break;

View File

@ -215,7 +215,7 @@ void Copter::tuning()
#endif #endif
case TUNING_RATE_YAW_FILT: 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; break;
#if WINCH_ENABLED == ENABLED #if WINCH_ENABLED == ENABLED