mirror of https://github.com/ArduPilot/ardupilot
Tracker: integrate AP_Stats library
This commit is contained in:
parent
d68e8f4cfb
commit
e5ea748e7f
|
@ -51,6 +51,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100),
|
||||
SCHED_TASK(one_second_loop, 1, 3900),
|
||||
SCHED_TASK_CLASS(Compass, &tracker.compass, cal_update, 50, 100),
|
||||
SCHED_TASK(stats_update, 1, 200),
|
||||
SCHED_TASK(accel_cal_update, 10, 100)
|
||||
};
|
||||
|
||||
|
@ -132,6 +133,15 @@ void Tracker::ten_hz_logging_loop()
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
update AP_Stats
|
||||
*/
|
||||
void Tracker::stats_update(void)
|
||||
{
|
||||
stats.set_flying(hal.util->get_soft_armed());
|
||||
stats.update();
|
||||
}
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
Tracker::Tracker(void)
|
||||
|
|
|
@ -267,6 +267,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||
MSG_AHRS,
|
||||
MSG_HWSTATUS,
|
||||
MSG_SIMSTATE,
|
||||
MSG_SYSTEM_TIME,
|
||||
MSG_AHRS2,
|
||||
MSG_AHRS3,
|
||||
MSG_MAG_CAL_REPORT,
|
||||
|
|
|
@ -409,6 +409,10 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(disarm_pwm, "SAFE_DISARM_PWM", 0),
|
||||
|
||||
// @Group: STAT_
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
GOBJECT(stats, "STAT", AP_Stats),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -108,6 +108,7 @@ public:
|
|||
k_param_rc_channels,
|
||||
k_param_servo_channels,
|
||||
|
||||
k_param_stats = 218,
|
||||
k_param_scripting = 219,
|
||||
|
||||
//
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
#include <AP_Mission/AP_Mission.h>
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AP_Rally/AP_Rally.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
|
@ -144,6 +145,8 @@ private:
|
|||
GCS_Tracker _gcs; // avoid using this; use gcs()
|
||||
GCS_Tracker &gcs() { return _gcs; }
|
||||
|
||||
AP_Stats stats;
|
||||
|
||||
AP_BoardConfig BoardConfig;
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
|
@ -208,6 +211,7 @@ private:
|
|||
// AntennaTracker.cpp
|
||||
void one_second_loop();
|
||||
void ten_hz_logging_loop();
|
||||
void stats_update();
|
||||
|
||||
// control_auto.cpp
|
||||
void update_auto(void);
|
||||
|
|
|
@ -20,6 +20,9 @@ void Tracker::init_tracker()
|
|||
// Check the EEPROM format version before loading any parameters from EEPROM
|
||||
load_parameters();
|
||||
|
||||
// initialise stats module
|
||||
stats.init();
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
// initialise serial ports
|
||||
|
|
|
@ -10,6 +10,7 @@ def build(bld):
|
|||
'AC_PID',
|
||||
'AP_Beacon',
|
||||
'AP_Arming',
|
||||
'AP_Stats',
|
||||
],
|
||||
)
|
||||
|
||||
|
|
Loading…
Reference in New Issue