From 38b19b9eeee3b69e1ce4bf25301411c4a4d910a3 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Tue, 2 May 2017 15:46:22 +0200 Subject: [PATCH] AP_NavEKF2: 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 --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 076a554010..ef5b310293 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -192,7 +192,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Range: 0 250 // @Increment: 10 // @User: Advanced - // @Units: milliseconds + // @Units: ms AP_GROUPINFO("GPS_DELAY", 8, NavEKF2, _gpsDelay_ms, 220), // Height measurement parameters @@ -227,7 +227,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Range: 0 250 // @Increment: 10 // @User: Advanced - // @Units: milliseconds + // @Units: ms AP_GROUPINFO("HGT_DELAY", 12, NavEKF2, _hgtDelay_ms, 60), // Magnetometer measurement parameters @@ -238,7 +238,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Range: 0.01 0.5 // @Increment: 0.01 // @User: Advanced - // @Units: gauss + // @Units: Gauss AP_GROUPINFO("MAG_M_NSE", 13, NavEKF2, _magNoise, MAG_M_NSE_DEFAULT), // @Param: MAG_CAL @@ -328,7 +328,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Range: 0 127 // @Increment: 10 // @User: Advanced - // @Units: milliseconds + // @Units: ms AP_GROUPINFO("FLOW_DELAY", 23, NavEKF2, _flowDelay_ms, FLOW_MEAS_DELAY), // State and Covariance Predition Parameters @@ -364,7 +364,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Description: This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier. // @Range: 0.000001 0.001 // @User: Advanced - // @Units: 1/s + // @Units: Hz AP_GROUPINFO("GSCL_P_NSE", 27, NavEKF2, _gyroScaleProcessNoise, GSCALE_P_NSE_DEFAULT), // @Param: ABIAS_P_NSE @@ -464,7 +464,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Description: This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier. // @Range: 0.00001 0.01 // @User: Advanced - // @Units: gauss/s + // @Units: Gauss/s AP_GROUPINFO("MAGE_P_NSE", 40, NavEKF2, _magEarthProcessNoise, MAGE_P_NSE_DEFAULT), // @Param: MAGB_P_NSE @@ -472,7 +472,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Description: This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier. // @Range: 0.00001 0.01 // @User: Advanced - // @Units: gauss/s + // @Units: Gauss/s AP_GROUPINFO("MAGB_P_NSE", 41, NavEKF2, _magBodyProcessNoise, MAGB_P_NSE_DEFAULT), // @Param: RNG_USE_HGT @@ -515,7 +515,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Range: 0 127 // @Increment: 10 // @User: Advanced - // @Units: milliseconds + // @Units: ms AP_GROUPINFO("BCN_DELAY", 46, NavEKF2, _rngBcnDelay_ms, 50), // @Param: RNG_USE_SPD