From adcc309f15865e392514783e7a9a0908572e77dd Mon Sep 17 00:00:00 2001 From: night-ghost Date: Wed, 28 Feb 2018 17:20:57 +0500 Subject: [PATCH] Copter: allow AP_Stats to be optional --- ArduCopter/ArduCopter.cpp | 2 ++ ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/Parameters.h | 2 ++ ArduCopter/config.h | 5 ++++- ArduCopter/land_detector.cpp | 2 ++ ArduCopter/system.cpp | 2 ++ 6 files changed, 14 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index ac46d39f14..6c17a8b4ba 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -176,7 +176,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(userhook_SuperSlowLoop, 1, 75), #endif SCHED_TASK_CLASS(AP_Button, &copter.g2.button, update, 5, 100), +#if STATS_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Stats, &copter.g2.stats, update, 1, 100), +#endif }; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index b2ea4bc8e8..02859d5f8c 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -905,11 +905,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Values: 0:NotEnforced,1:Enforced // @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 GRIPPER_ENABLED == ENABLED // @Group: GRIP_ // @Path: ../libraries/AP_Gripper/AP_Gripper.cpp diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 078fa7859e..f63f6e31cb 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -498,8 +498,10 @@ public: // button checking AP_Button button; +#if STATS_ENABLED == ENABLED // vehicle statistics AP_Stats stats; +#endif #if GRIPPER_ENABLED AP_Gripper gripper; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index fa1cd38e1d..45bdec11e2 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -693,7 +693,10 @@ #define TOY_MODE_ENABLED DISABLED #endif - #if TOY_MODE_ENABLED && FRAME_CONFIG == HELI_FRAME #error Toy mode is not available on Helicopters #endif + +#ifndef STATS_ENABLED + # define STATS_ENABLED ENABLED +#endif diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 7866e3aaa2..7b9ed92d72 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -104,7 +104,9 @@ void Copter::set_land_complete(bool b) } ap.land_complete = b; +#if STATS_ENABLED == ENABLED g2.stats.set_flying(!b); +#endif // tell AHRS flying state ahrs.set_likely_flying(!b); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 3a06fc49aa..8218b4848c 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -52,8 +52,10 @@ void Copter::init_ardupilot() // actual loop rate G_Dt = 1.0 / scheduler.get_loop_rate_hz(); +#if STATS_ENABLED == ENABLED // initialise stats module g2.stats.init(); +#endif gcs().set_dataflash(&DataFlash);