mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: move AP_Stats to AP_Vehicle
This commit is contained in:
parent
c84e5b337e
commit
652d2ec198
|
@ -251,6 +251,13 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
|
|||
// @Path: ../Filter/AP_Filter.cpp
|
||||
AP_SUBGROUPINFO(filters, "FILT", 26, AP_Vehicle, AP_Filters),
|
||||
#endif
|
||||
|
||||
#if AP_STATS_ENABLED
|
||||
// @Group: STAT
|
||||
// @Path: ../AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 27, AP_Vehicle, AP_Stats),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -346,6 +353,11 @@ void AP_Vehicle::setup()
|
|||
generator.init();
|
||||
#endif
|
||||
|
||||
#if AP_STATS_ENABLED
|
||||
// initialise stats module
|
||||
stats.init();
|
||||
#endif
|
||||
|
||||
// init_ardupilot is where the vehicle does most of its initialisation.
|
||||
init_ardupilot();
|
||||
|
||||
|
@ -573,6 +585,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
|
|||
#endif
|
||||
#if AP_FILTER_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Filters, &vehicle.filters, update, 1, 100, 252),
|
||||
#endif
|
||||
#if AP_STATS_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &vehicle.stats, update, 1, 100, 252),
|
||||
#endif
|
||||
SCHED_TASK(update_arming, 1, 50, 253),
|
||||
};
|
||||
|
|
|
@ -68,6 +68,7 @@
|
|||
#include <Filter/LowPassFilter.h>
|
||||
#include <AP_KDECAN/AP_KDECAN.h>
|
||||
#include <Filter/AP_Filter.h>
|
||||
#include <AP_Stats/AP_Stats.h> // statistics library
|
||||
|
||||
class AP_DDS_Client;
|
||||
|
||||
|
@ -388,6 +389,11 @@ protected:
|
|||
AP_Airspeed airspeed;
|
||||
#endif
|
||||
|
||||
#if AP_STATS_ENABLED
|
||||
// vehicle statistics
|
||||
AP_Stats stats;
|
||||
#endif
|
||||
|
||||
#if AP_AIS_ENABLED
|
||||
// Automatic Identification System - for tracking sea-going vehicles
|
||||
AP_AIS ais;
|
||||
|
|
Loading…
Reference in New Issue