mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_Stats: NFC Statistics are read-only variables
This commit is contained in:
parent
ccee841578
commit
ca72f4d283
@ -10,6 +10,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
||||
// @Param: _BOOTCNT
|
||||
// @DisplayName: Boot Count
|
||||
// @Description: Number of times board has been booted
|
||||
// @ReadOnly: True
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_BOOTCNT", 0, AP_Stats, params.bootcount, 0),
|
||||
|
||||
@ -17,6 +18,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
||||
// @DisplayName: Total FlightTime
|
||||
// @Description: Total FlightTime (seconds)
|
||||
// @Units: s
|
||||
// @ReadOnly: True
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_FLTTIME", 1, AP_Stats, params.flttime, 0),
|
||||
|
||||
@ -24,6 +26,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
||||
// @DisplayName: Total RunTime
|
||||
// @Description: Total time autopilot has run
|
||||
// @Units: s
|
||||
// @ReadOnly: True
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_RUNTIME", 2, AP_Stats, params.runtime, 0),
|
||||
|
||||
@ -31,6 +34,7 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
||||
// @DisplayName: Reset time
|
||||
// @Description: Seconds since January 1st 2016 (Unix epoch+1451606400) since reset (set to 0 to reset statistics)
|
||||
// @Units: s
|
||||
// @ReadOnly: True
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_RESET", 3, AP_Stats, params.reset, 1),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user