diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 007a0d4386..65e250ff9f 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -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),