Copter: use AP_Stats to store statistics about vehicle

This commit is contained in:
Peter Barker 2016-10-13 17:30:30 +11:00 committed by Randy Mackay
parent 7eff99b053
commit df07cb525a
6 changed files with 15 additions and 2 deletions

View File

@ -60,6 +60,7 @@
#include <AP_Motors/AP_Motors.h> // AP Motors library #include <AP_Motors/AP_Motors.h> // AP Motors library
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library #include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
#include <AP_Proximity/AP_Proximity.h> #include <AP_Proximity/AP_Proximity.h>
#include <AP_Stats/AP_Stats.h> // statistics library
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library #include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
#include <AP_RSSI/AP_RSSI.h> // RSSI Library #include <AP_RSSI/AP_RSSI.h> // RSSI Library
#include <Filter/Filter.h> // Filter library #include <Filter/Filter.h> // Filter library

View File

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

View File

@ -550,6 +550,9 @@ public:
// button checking // button checking
AP_Button button; AP_Button button;
// vehicle statistics
AP_Stats stats;
// Throw mode parameters // Throw mode parameters
AP_Int8 throw_nextmode; AP_Int8 throw_nextmode;
AP_Int8 throw_type; AP_Int8 throw_type;

View File

@ -62,3 +62,4 @@ LIBRARIES += AC_InputManager
LIBRARIES += AP_ADSB LIBRARIES += AP_ADSB
LIBRARIES += AP_Avoidance LIBRARIES += AP_Avoidance
LIBRARIES += AP_Proximity LIBRARIES += AP_Proximity
LIBRARIES += AP_Stats

View File

@ -108,6 +108,9 @@ void Copter::init_ardupilot()
// load parameters from EEPROM // load parameters from EEPROM
load_parameters(); load_parameters();
// initialise stats module
g2.stats.init();
GCS_MAVLINK::set_dataflash(&DataFlash); GCS_MAVLINK::set_dataflash(&DataFlash);
// identify ourselves correctly with the ground station // identify ourselves correctly with the ground station

View File

@ -30,7 +30,8 @@ def build(bld):
'AP_ServoRelayEvents', 'AP_ServoRelayEvents',
'AP_Avoidance', 'AP_Avoidance',
'AP_AdvancedFailsafe', 'AP_AdvancedFailsafe',
'AP_Proximity' 'AP_Proximity',
'AP_Stats',
], ],
) )