mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: use iterators in parameter conversion
This commit is contained in:
parent
3582b69e9c
commit
9e7a0e6267
@ -1241,24 +1241,20 @@ void Copter::convert_pid_parameters(void)
|
||||
#endif
|
||||
|
||||
// scale PID gains
|
||||
uint8_t table_size = ARRAY_SIZE(pid_conversion_info);
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&pid_conversion_info[i], pid_scaler);
|
||||
for (const auto &info : pid_conversion_info) {
|
||||
AP_Param::convert_old_parameter(&info, pid_scaler);
|
||||
}
|
||||
// reduce IMAX into -1 ~ +1 range
|
||||
table_size = ARRAY_SIZE(imax_conversion_info);
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&imax_conversion_info[i], 1.0f/4500.0f);
|
||||
for (const auto &info : imax_conversion_info) {
|
||||
AP_Param::convert_old_parameter(&info, 1.0f/4500.0f);
|
||||
}
|
||||
// convert angle controller gain and filter without scaling
|
||||
table_size = ARRAY_SIZE(angle_and_filt_conversion_info);
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&angle_and_filt_conversion_info[i], 1.0f);
|
||||
for (const auto &info : angle_and_filt_conversion_info) {
|
||||
AP_Param::convert_old_parameter(&info, 1.0f);
|
||||
}
|
||||
// convert throttle parameters (multicopter only)
|
||||
table_size = ARRAY_SIZE(throttle_conversion_info);
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&throttle_conversion_info[i], 0.001f);
|
||||
for (const auto &info : throttle_conversion_info) {
|
||||
AP_Param::convert_old_parameter(&info, 0.001f);
|
||||
}
|
||||
// convert RC_FEEL_RP to ATC_INPUT_TC
|
||||
const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" };
|
||||
@ -1267,9 +1263,8 @@ void Copter::convert_pid_parameters(void)
|
||||
AP_Param::set_default_by_name(rc_feel_rp_conversion_info.new_name, (1.0f / (2.0f + rc_feel_rp_old.get() * 0.1f)));
|
||||
}
|
||||
// convert loiter parameters
|
||||
table_size = ARRAY_SIZE(loiter_conversion_info);
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&loiter_conversion_info[i], 1.0f);
|
||||
for (const auto &info : loiter_conversion_info) {
|
||||
AP_Param::convert_old_parameter(&info, 1.0f);
|
||||
}
|
||||
|
||||
// TradHeli default parameters
|
||||
|
Loading…
Reference in New Issue
Block a user