From 7a14427d2696e6728690ff47839b6b52c9223367 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 30 Jan 2024 13:41:43 +1100 Subject: [PATCH] Tracker: move scripting up to AP_Vehicle --- AntennaTracker/Parameters.cpp | 11 +++++------ AntennaTracker/Parameters.h | 2 +- AntennaTracker/Tracker.h | 8 -------- AntennaTracker/system.cpp | 4 ---- 4 files changed, 6 insertions(+), 19 deletions(-) diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 20d8da47aa..c21d5dbf4f 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -505,12 +505,6 @@ const AP_Param::Info Tracker::var_info[] = { GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), -#if AP_SCRIPTING_ENABLED - // @Group: SCR_ - // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp - GOBJECT(scripting, "SCR_", AP_Scripting), -#endif - // @Param: CMD_TOTAL // @DisplayName: Number of loaded mission items // @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually. @@ -619,6 +613,11 @@ void Tracker::load_parameters(void) AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true); #endif +#if AP_SCRIPTING_ENABLED + // PARAMETER_CONVERSION - Added: Jan-2024 + AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true); +#endif + hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before)); #if HAL_HAVE_SAFETY_SWITCH diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 836a708536..1db980b04a 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -115,7 +115,7 @@ public: k_param_servo_channels, k_param_stats_old = 218, - k_param_scripting = 219, + k_param_scripting_old = 219, // // 220: Waypoint data diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 54b2719433..22c7687ef7 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -53,10 +53,6 @@ #include "AP_Arming.h" -#if AP_SCRIPTING_ENABLED -#include -#endif - #include "mode.h" class Tracker : public AP_Vehicle { @@ -115,10 +111,6 @@ private: ModeServoTest mode_servotest; ModeStop mode_stop; -#if AP_SCRIPTING_ENABLED - AP_Scripting scripting; -#endif - // Vehicle state struct { bool location_valid; // true if we have a valid location for the vehicle diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index a05be96b61..db4438ded4 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -28,10 +28,6 @@ void Tracker::init_ardupilot() log_init(); #endif -#if AP_SCRIPTING_ENABLED - scripting.init(); -#endif // AP_SCRIPTING_ENABLED - // initialise compass AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init();