mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: parameter conversion from RC_FEEL_RP to ATC_INPUT_TC
This commit is contained in:
parent
8ac653cabf
commit
f368ff6664
@ -1175,6 +1175,12 @@ void Copter::convert_pid_parameters(void)
|
||||
for (uint8_t i=0; i<table_size; i++) {
|
||||
AP_Param::convert_old_parameter(&throttle_conversion_info[i], 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" };
|
||||
AP_Int8 rc_feel_rp_old;
|
||||
if (AP_Param::find_old_parameter(&rc_feel_rp_conversion_info, &rc_feel_rp_old)) {
|
||||
AP_Param::set_default_by_name(rc_feel_rp_conversion_info.new_name, (1.0f / (2.0f + rc_feel_rp_old.get() / 10.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,
|
||||
|
Loading…
Reference in New Issue
Block a user