Browse Source

Copter: added automatic SRV_Channel parameter upgrade

master
Andrew Tridgell 8 years ago
parent
commit
3c1517f583
  1. 11
      ArduCopter/Parameters.cpp

11
ArduCopter/Parameters.cpp

@ -1162,4 +1162,15 @@ void Copter::convert_pid_parameters(void) @@ -1162,4 +1162,15 @@ 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);
}
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_5_old, Parameters::k_param_rc_6_old,
Parameters::k_param_rc_7_old, Parameters::k_param_rc_8_old,
Parameters::k_param_rc_9_old, Parameters::k_param_rc_10_old,
Parameters::k_param_rc_11_old, Parameters::k_param_rc_12_old,
Parameters::k_param_rc_13_old, Parameters::k_param_rc_14_old };
const uint16_t old_aux_chan_mask = 0x3FF0;
// note that we don't pass in rcmap as we don't want output channel functions changed based on rcmap
SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, nullptr);
}

Loading…
Cancel
Save