mirror of https://github.com/ArduPilot/ardupilot
Copter: tradheli update conversion
This commit is contained in:
parent
d4fec221c3
commit
aef04fd924
|
@ -1398,15 +1398,15 @@ void Copter::convert_tradheli_parameters(void)
|
|||
} else if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL) {
|
||||
// dual heli conversion info
|
||||
const AP_Param::ConversionInfo dualheli_conversion_info[] = {
|
||||
{ Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW1_H3_SV1_POS" },
|
||||
{ Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW1_H3_SV2_POS" },
|
||||
{ Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW1_H3_SV3_POS" },
|
||||
{ Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW_H3_SV1_POS" },
|
||||
{ Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW_H3_SV2_POS" },
|
||||
{ Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW_H3_SV3_POS" },
|
||||
{ Parameters::k_param_motors, 4, AP_PARAM_INT16, "H_SW2_H3_SV1_POS" },
|
||||
{ Parameters::k_param_motors, 5, AP_PARAM_INT16, "H_SW2_H3_SV2_POS" },
|
||||
{ Parameters::k_param_motors, 6, AP_PARAM_INT16, "H_SW2_H3_SV3_POS" },
|
||||
{ Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW1_H3_PHANG" },
|
||||
{ Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW_H3_PHANG" },
|
||||
{ Parameters::k_param_motors, 8, AP_PARAM_INT16, "H_SW2_H3_PHANG" },
|
||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW1_COL_DIR" },
|
||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW_COL_DIR" },
|
||||
{ Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW2_COL_DIR" },
|
||||
};
|
||||
|
||||
|
@ -1435,13 +1435,13 @@ void Copter::convert_tradheli_parameters(void)
|
|||
// find the new variable in the variable structures
|
||||
enum ap_var_type ptype;
|
||||
AP_Param *ap2;
|
||||
ap2 = AP_Param::find("H_SW1_TYPE", &ptype);
|
||||
ap2 = AP_Param::find("H_SW_TYPE", &ptype);
|
||||
// make sure the pointer is valid
|
||||
if (ap2 != nullptr) {
|
||||
// see if we can load it from EEPROM
|
||||
if (!ap2->configured_in_storage()) {
|
||||
// the new parameter is not in storage so set generic swash
|
||||
AP_Param::set_and_save_by_name("H_SW1_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3);
|
||||
AP_Param::set_and_save_by_name("H_SW_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue