Plane: support for AP_Stats (flight time, bootcount, runtime)

This commit is contained in:
Peter Barker 2016-10-26 12:24:41 +11:00 committed by Randy Mackay
parent 1bd96ae558
commit 98ae6c776a
8 changed files with 27 additions and 2 deletions

View File

@ -82,8 +82,18 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(dataflash_periodic, 50, 400),
SCHED_TASK(avoidance_adsb_update, 10, 100),
SCHED_TASK(button_update, 5, 100),
SCHED_TASK(stats_update, 1, 100),
};
/*
update AP_Stats
*/
void Plane::stats_update(void)
{
g2.stats.update();
}
void Plane::setup()
{
cliSerial = hal.console;

View File

@ -1386,7 +1386,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Values: 0:NotEnforced,1:Enforced
// @User: Advanced
AP_GROUPINFO("SYSID_ENFORCE", 4, ParametersG2, sysid_enforce, 0),
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO(stats, "STAT", 5, ParametersG2, AP_Stats),
AP_GROUPEND
};

View File

@ -582,6 +582,9 @@ public:
// button reporting library
AP_Button button;
// vehicle statistics
AP_Stats stats;
// internal combustion engine control
AP_ICEngine ice_control;

View File

@ -52,6 +52,7 @@
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RPM/AP_RPM.h>
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
#include <APM_Control/APM_Control.h>
@ -983,6 +984,7 @@ private:
void read_receiver_rssi(void);
void rpm_update(void);
void button_update(void);
void stats_update();
void ice_update(void);
void report_radio();
void report_ins();

View File

@ -156,6 +156,7 @@ void Plane::update_is_flying_5Hz(void)
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.set_is_flying(new_is_flying);
#endif
g2.stats.set_flying(new_is_flying);
crash_detection_update();

View File

@ -59,3 +59,4 @@ LIBRARIES += AC_Fence
LIBRARIES += AC_Avoidance
LIBRARIES += AP_Proximity
LIBRARIES += AP_Tuning
LIBRARIES += AP_Stats

View File

@ -88,6 +88,9 @@ void Plane::init_ardupilot()
//
load_parameters();
// initialise stats module
g2.stats.init();
#if HIL_SUPPORT
if (g.hil_mode == 1) {
// set sensors to HIL mode

View File

@ -30,7 +30,8 @@ def build(bld):
'AC_PID',
'AC_Fence',
'AC_Avoidance',
'AP_Proximity'
'AP_Proximity',
'AP_Stats',
],
)