|
|
|
@ -500,9 +500,11 @@ const AP_Param::Info Copter::var_info[] = {
@@ -500,9 +500,11 @@ const AP_Param::Info Copter::var_info[] = {
|
|
|
|
|
GOBJECT(parachute, "CHUTE_", AP_Parachute), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if LANDING_GEAR_ENABLED == ENABLED |
|
|
|
|
// @Group: LGR_
|
|
|
|
|
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
|
|
|
|
GOBJECT(landinggear, "LGR_", AP_LandingGear), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
// @Group: IM_
|
|
|
|
@ -1161,8 +1163,10 @@ void Copter::load_parameters(void)
@@ -1161,8 +1163,10 @@ void Copter::load_parameters(void)
|
|
|
|
|
AP_Param::load_all(); |
|
|
|
|
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table)); |
|
|
|
|
|
|
|
|
|
#if LANDING_GEAR_ENABLED == ENABLED |
|
|
|
|
// convert landing gear parameters
|
|
|
|
|
convert_lgr_parameters(); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// convert fs_options parameters
|
|
|
|
|
convert_fs_options_params(); |
|
|
|
@ -1334,6 +1338,7 @@ void Copter::convert_pid_parameters(void)
@@ -1334,6 +1338,7 @@ void Copter::convert_pid_parameters(void)
|
|
|
|
|
SRV_Channels::upgrade_parameters(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if LANDING_GEAR_ENABLED == ENABLED |
|
|
|
|
/*
|
|
|
|
|
convert landing gear parameters |
|
|
|
|
*/ |
|
|
|
@ -1415,6 +1420,7 @@ void Copter::convert_lgr_parameters(void)
@@ -1415,6 +1420,7 @@ void Copter::convert_lgr_parameters(void)
|
|
|
|
|
servo_reversed->set_and_save_ifchanged(1); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
// handle conversion of tradheli parameters from Copter-3.6 to Copter-3.7
|
|
|
|
|