From 6a12ed0d65031c8d0741b77179a6286d7bbf430f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 10 Jan 2017 16:09:58 +1100 Subject: [PATCH] Copter: upgrade heli servo parameters --- ArduCopter/Parameters.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 139dd4d8c6..c58ad5b702 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1163,5 +1163,13 @@ void Copter::convert_pid_parameters(void) 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); + if (SRV_Channels::upgrade_parameters(old_rc_keys, old_aux_chan_mask, nullptr)) { + // do frame specific upgrade +#if FRAME_CONFIG == HELI_FRAME + SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 12, CH_1); + SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 13, CH_2); + SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 14, CH_3); + SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 15, CH_4); +#endif + } }