Copter: convert THR_MIN to MOT_SPIN_MIN, THR_MID to MOT_THST_HOVER
This commit is contained in:
parent
48eb4cf674
commit
901e8cc23f
@ -1049,6 +1049,10 @@ void Copter::convert_pid_parameters(void)
|
||||
{ Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" },
|
||||
{ Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" }
|
||||
};
|
||||
AP_Param::ConversionInfo throttle_conversion_info[] = {
|
||||
{ Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" },
|
||||
{ Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" }
|
||||
};
|
||||
|
||||
// gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees
|
||||
// and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
|
||||
@ -1076,4 +1080,9 @@ void Copter::convert_pid_parameters(void)
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&angle_and_filt_conversion_info[i], 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);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user