Browse Source

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

mission-4.1.18
Peter Barker 8 years ago committed by Randy Mackay
parent
commit
36c0bacada
  1. 10
      APMrover2/APMrover2.cpp
  2. 4
      APMrover2/Parameters.cpp
  3. 3
      APMrover2/Parameters.h
  4. 2
      APMrover2/Rover.h
  5. 2
      APMrover2/make.inc
  6. 3
      APMrover2/system.cpp
  7. 1
      APMrover2/wscript

10
APMrover2/APMrover2.cpp

@ -75,8 +75,18 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { @@ -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
*/

4
APMrover2/Parameters.cpp

@ -566,6 +566,10 @@ const AP_Param::Info Rover::var_info[] = { @@ -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
};

3
APMrover2/Parameters.h

@ -331,6 +331,9 @@ public: @@ -331,6 +331,9 @@ public:
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];
// vehicle statistics
AP_Stats stats;
};

2
APMrover2/Rover.h

@ -72,6 +72,7 @@ @@ -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: @@ -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();

2
APMrover2/make.inc

@ -46,4 +46,4 @@ LIBRARIES += AP_RSSI @@ -46,4 +46,4 @@ LIBRARIES += AP_RSSI
LIBRARIES += AP_Declination
LIBRARIES += AP_RPM
LIBRARIES += AP_Arming
LIBRARIES += AP_Stats

3
APMrover2/system.cpp

@ -89,6 +89,9 @@ void Rover::init_ardupilot() @@ -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;

1
APMrover2/wscript

@ -20,6 +20,7 @@ def build(bld): @@ -20,6 +20,7 @@ def build(bld):
'AP_Relay',
'AP_ServoRelayEvents',
'PID',
'AP_Stats',
],
)

Loading…
Cancel
Save