diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index bdd901706b..9b89e93abc 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -9,7 +9,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands -//#define STATS_ENABLED DISABLED // disable statistics support //#define MODE_ACRO_ENABLED DISABLED // disable acrobatic mode support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support //#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 740bb95e5f..70bc6be0c4 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -260,9 +260,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if HAL_BUTTON_ENABLED SCHED_TASK_CLASS(AP_Button, &copter.button, update, 5, 100, 168), #endif -#if STATS_ENABLED == ENABLED - SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100, 171), -#endif }; void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 8685f4cb8f..4632cec087 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -47,7 +47,6 @@ #include // Position control library #include // Command model library #include // AP Motors library -#include // statistics library #include // Filter library #include // needed for AHRS build #include // inertial navigation library diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index d1de6fe45d..e8c2d50396 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -821,12 +821,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0), -#if STATS_ENABLED == ENABLED - // @Group: STAT - // @Path: ../libraries/AP_Stats/AP_Stats.cpp - AP_SUBGROUPINFO(stats, "STAT", 12, ParametersG2, AP_Stats), -#endif - #if AP_GRIPPER_ENABLED // @Group: GRIP_ // @Path: ../libraries/AP_Gripper/AP_Gripper.cpp @@ -1382,6 +1376,21 @@ void Copter::load_parameters(void) AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true); #endif + // PARAMETER_CONVERSION - Added: Jan-2024 for Copter-4.6 +#if AP_STATS_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 = 12; // Old parameter index in g2 + const uint16_t old_top_element = 4044; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) + AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false); + } +#endif + hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); // setup AP_Param frame type flags diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 3d8b62b96d..5ac04f8946 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -508,11 +508,6 @@ public: AP_Button *button_ptr; #endif -#if STATS_ENABLED == ENABLED - // vehicle statistics - AP_Stats stats; -#endif - #if AP_GRIPPER_ENABLED AP_Gripper gripper; #endif diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 97793741c9..3952cf8722 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -617,10 +617,6 @@ #error Toy mode is not available on Helicopters #endif -#ifndef STATS_ENABLED - # define STATS_ENABLED ENABLED -#endif - #ifndef OSD_ENABLED #define OSD_ENABLED DISABLED #endif diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 4a4cdd3fca..1c241f67b7 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -1,5 +1,7 @@ #include "Copter.h" +#include // statistics library + // Code to detect a crash main ArduCopter code #define LAND_CHECK_ANGLE_ERROR_DEG 30.0f // maximum angle error to be considered landing #define LAND_CHECK_LARGE_ANGLE_CD 1500.0f // maximum angle target to be considered landing @@ -148,8 +150,8 @@ void Copter::set_land_complete(bool b) #endif ap.land_complete = b; -#if STATS_ENABLED == ENABLED - g2.stats.set_flying(!b); +#if AP_STATS_ENABLED + AP::stats()->set_flying(!b); #endif // tell AHRS flying state diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 83c4cbf5b8..eaf86120af 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -16,11 +16,6 @@ static void failsafe_check_static() void Copter::init_ardupilot() { -#if STATS_ENABLED == ENABLED - // initialise stats module - g2.stats.init(); -#endif - BoardConfig.init(); #if HAL_MAX_CAN_PROTOCOL_DRIVERS can_mgr.init();