mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Copter: added conversion of tricopter tail servo parameters
This commit is contained in:
parent
05e9462a9c
commit
7aee3500e1
@ -1164,12 +1164,25 @@ void Copter::convert_pid_parameters(void)
|
|||||||
const uint16_t old_aux_chan_mask = 0x3FF0;
|
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
|
// note that we don't pass in rcmap as we don't want output channel functions changed based on rcmap
|
||||||
if (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
|
// do frame specific upgrade. This is only done the first time we run the new firmware
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#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, 12, CH_1);
|
||||||
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 13, CH_2);
|
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, 14, CH_3);
|
||||||
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 15, CH_4);
|
SRV_Channels::upgrade_motors_servo(Parameters::k_param_motors, 15, CH_4);
|
||||||
|
#else
|
||||||
|
if (g2.frame_class == AP_Motors::MOTOR_FRAME_TRI) {
|
||||||
|
const AP_Param::ConversionInfo tri_conversion_info[] = {
|
||||||
|
{ Parameters::k_param_motors, 32, AP_PARAM_INT16, "SERVO7_TRIM" },
|
||||||
|
{ Parameters::k_param_motors, 33, AP_PARAM_INT16, "SERVO7_MIN" },
|
||||||
|
{ Parameters::k_param_motors, 34, AP_PARAM_INT16, "SERVO7_MAX" },
|
||||||
|
{ Parameters::k_param_motors, 35, AP_PARAM_FLOAT, "MOT_YAW_SV_ANGLE" },
|
||||||
|
};
|
||||||
|
// we need to use CONVERT_FLAG_FORCE as the SERVO7_* parameters will already be set from RC7_*
|
||||||
|
AP_Param::convert_old_parameters(tri_conversion_info, ARRAY_SIZE(tri_conversion_info), AP_Param::CONVERT_FLAG_FORCE);
|
||||||
|
const AP_Param::ConversionInfo tri_conversion_info_rev { Parameters::k_param_motors, 31, AP_PARAM_INT8, "SERVO7_REVERSED" };
|
||||||
|
AP_Param::convert_old_parameter(&tri_conversion_info_rev, 1, AP_Param::CONVERT_FLAG_REVERSE | AP_Param::CONVERT_FLAG_FORCE);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user