Rover: support for AP_Stats (flight time, bootcount, runtime)
This commit is contained in:
parent
f1b776e4eb
commit
36c0bacada
@ -75,8 +75,18 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(accel_cal_update, 10, 100),
|
||||
SCHED_TASK(dataflash_periodic, 50, 300),
|
||||
SCHED_TASK(button_update, 5, 100),
|
||||
SCHED_TASK(stats_update, 1, 100),
|
||||
};
|
||||
|
||||
/*
|
||||
update AP_Stats
|
||||
*/
|
||||
void Rover::stats_update(void)
|
||||
{
|
||||
g2.stats.set_flying(motor_active());
|
||||
g2.stats.update();
|
||||
}
|
||||
|
||||
/*
|
||||
setup is called when the sketch starts
|
||||
*/
|
||||
|
@ -566,6 +566,10 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
*/
|
||||
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -331,6 +331,9 @@ public:
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
@ -72,6 +72,7 @@
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
|
||||
#include <AP_Button/AP_Button.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
|
||||
// Configuration
|
||||
#include "config.h"
|
||||
@ -472,6 +473,7 @@ private:
|
||||
void read_trim_switch();
|
||||
void update_events(void);
|
||||
void button_update(void);
|
||||
void stats_update();
|
||||
void navigate();
|
||||
void set_control_channels(void);
|
||||
void init_rc_in();
|
||||
|
@ -46,4 +46,4 @@ LIBRARIES += AP_RSSI
|
||||
LIBRARIES += AP_Declination
|
||||
LIBRARIES += AP_RPM
|
||||
LIBRARIES += AP_Arming
|
||||
|
||||
LIBRARIES += AP_Stats
|
||||
|
@ -89,6 +89,9 @@ void Rover::init_ardupilot()
|
||||
|
||||
load_parameters();
|
||||
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
|
||||
GCS_MAVLINK::set_dataflash(&DataFlash);
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
@ -20,6 +20,7 @@ def build(bld):
|
||||
'AP_Relay',
|
||||
'AP_ServoRelayEvents',
|
||||
'PID',
|
||||
'AP_Stats',
|
||||
],
|
||||
)
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user