mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AP_Stats: Use SI units conventions in parameter units
Follow the rules from: http://physics.nist.gov/cuu/Units/units.html http://physics.nist.gov/cuu/Units/outside.html and http://physics.nist.gov/cuu/Units/checklist.html one further constrain is that only printable (7bit) ASCII characters are allowed
This commit is contained in:
parent
b4244efb87
commit
c417376ba8
@ -16,21 +16,21 @@ const AP_Param::GroupInfo AP_Stats::var_info[] = {
|
||||
// @Param: _FLTTIME
|
||||
// @DisplayName: Total FlightTime
|
||||
// @Description: Total FlightTime (seconds)
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_FLTTIME", 1, AP_Stats, params.flttime, 0),
|
||||
|
||||
// @Param: _RUNTIME
|
||||
// @DisplayName: Total RunTime
|
||||
// @Description: Total time autopilot has run
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @User: Standard
|
||||
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)
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_RESET", 3, AP_Stats, params.reset, 1),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user