mirror of https://github.com/ArduPilot/ardupilot
AP_Stats: Improve reset documentation (NFC)
This commit is contained in:
parent
a90f94d5a7
commit
3bea6229ad
|
@ -32,8 +32,8 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
|||
AP_GROUPINFO("_RUNTIME", 2, AP_Stats, params.runtime, 0),
|
||||
|
||||
// @Param: _RESET
|
||||
// @DisplayName: Reset time
|
||||
// @Description: Seconds since January 1st 2016 (Unix epoch+1451606400) since reset (set to 0 to reset statistics)
|
||||
// @DisplayName: Statistics Reset Time
|
||||
// @Description: Seconds since January 1st 2016 (Unix epoch+1451606400) since statistics reset (set to 0 to reset statistics)
|
||||
// @Units: s
|
||||
// @ReadOnly: True
|
||||
// @User: Standard
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
// init() to set initial values from the parameters!
|
||||
uint32_t flttime; // seconds in flight (or driving)
|
||||
uint32_t runtime; // total wallclock time spent running ArduPilot (seconds)
|
||||
uint32_t reset; // last time parameters were reset
|
||||
uint32_t reset; // last time AP_Stats parameters were reset (in seconds since AP_Stats Jan 1st 2016)
|
||||
uint32_t flttime_boot; // seconds in flight (or driving), at boot
|
||||
|
||||
void init();
|
||||
|
|
Loading…
Reference in New Issue