diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 113539dd17..639aa73039 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1100,11 +1100,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0), -#if AP_SCRIPTING_ENABLED - // @Group: SCR_ - // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp - AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting), -#endif + // 14 was AP_Scripting // @Param: TKOFF_ACCEL_CNT // @DisplayName: Takeoff throttle acceleration count @@ -1568,6 +1564,20 @@ void Plane::load_parameters(void) AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false); } #endif + // PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6 +#if AP_SCRIPTING_ENABLED + { + // Find G2's Top Level Key + AP_Param::ConversionInfo info; + if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { + return; + } + + const uint16_t old_index = 14; // Old parameter index in g2 + const uint16_t old_top_element = 78; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) + AP_Param::convert_class(info.old_key, &scripting, scripting.var_info, old_index, old_top_element, false); + } +#endif hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 4a80e21943..ad78f76de7 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -519,10 +519,6 @@ public: AP_Int32 flight_options; -#if AP_SCRIPTING_ENABLED - AP_Scripting scripting; -#endif // AP_SCRIPTING_ENABLED - AP_Int8 takeoff_throttle_accel_count; AP_Int8 takeoff_timeout; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 4b46bd837d..56998c3679 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -176,10 +176,6 @@ void Plane::startup_ground(void) ); #endif -#if AP_SCRIPTING_ENABLED - g2.scripting.init(); -#endif // AP_SCRIPTING_ENABLED - // reset last heartbeat time, so we don't trigger failsafe on slow // startup gcs().sysid_myggcs_seen(AP_HAL::millis());