Copter: allow AP_Stats to be optional

This commit is contained in:
night-ghost 2018-02-28 17:20:57 +05:00 committed by Andrew Tridgell
parent dbe860152d
commit adcc309f15
6 changed files with 14 additions and 3 deletions

View File

@ -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
};

View File

@ -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

View File

@ -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;

View File

@ -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

View File

@ -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);

View File

@ -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);