mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: allow AP_Stats to be optional
This commit is contained in:
parent
adcc309f15
commit
98b8a61ca8
@ -83,12 +83,15 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(ins_periodic, 50, 50),
|
||||
SCHED_TASK(avoidance_adsb_update, 10, 100),
|
||||
SCHED_TASK(button_update, 5, 100),
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK(stats_update, 1, 100),
|
||||
#endif
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75),
|
||||
#endif
|
||||
};
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
/*
|
||||
update AP_Stats
|
||||
*/
|
||||
@ -96,7 +99,7 @@ void Plane::stats_update(void)
|
||||
{
|
||||
g2.stats.update();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void Plane::setup()
|
||||
{
|
||||
|
@ -1144,10 +1144,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @Values: 0:NotEnforced,1:Enforced
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SYSID_ENFORCE", 4, ParametersG2, sysid_enforce, 0),
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 5, ParametersG2, AP_Stats),
|
||||
#endif
|
||||
|
||||
// @Group: SERVO
|
||||
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
||||
|
@ -518,8 +518,10 @@ public:
|
||||
// button reporting library
|
||||
AP_Button button;
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
#endif
|
||||
|
||||
// internal combustion engine control
|
||||
AP_ICEngine ice_control;
|
||||
|
@ -355,3 +355,7 @@
|
||||
#else
|
||||
# define HAVE_PX4_MIXER 0
|
||||
#endif
|
||||
|
||||
#ifndef STATS_ENABLED
|
||||
# define STATS_ENABLED ENABLED
|
||||
#endif
|
||||
|
@ -150,7 +150,9 @@ void Plane::update_is_flying_5Hz(void)
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.set_is_flying(new_is_flying);
|
||||
#endif
|
||||
#if STATS_ENABLED == ENABLED
|
||||
g2.stats.set_flying(new_is_flying);
|
||||
#endif
|
||||
|
||||
crash_detection_update();
|
||||
|
||||
|
@ -33,8 +33,10 @@ void Plane::init_ardupilot()
|
||||
//
|
||||
load_parameters();
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
#endif
|
||||
|
||||
#if HIL_SUPPORT
|
||||
if (g.hil_mode == 1) {
|
||||
|
Loading…
Reference in New Issue
Block a user