From 948bed6b5c017adbd78932a88e7c93d924411101 Mon Sep 17 00:00:00 2001 From: Nicolas Martin Date: Fri, 2 Oct 2020 15:33:05 +0200 Subject: [PATCH] fix ekf2 saved mag bias comments (mGauss -> Gauss) --- src/lib/parameters/px4params/srcparser.py | 2 +- src/modules/ekf2/EKF2.hpp | 12 ++++++------ src/modules/ekf2/ekf2_params.c | 8 ++++---- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/lib/parameters/px4params/srcparser.py b/src/lib/parameters/px4params/srcparser.py index 750e236d87..bee25314c4 100644 --- a/src/lib/parameters/px4params/srcparser.py +++ b/src/lib/parameters/px4params/srcparser.py @@ -352,7 +352,7 @@ class SourceParser(object): 'rad', '%/rad', 'rad/s', 'rad/s^2', '%/rad/s', 'rad s^2/m','rad s/m', 'bit/s', 'B/s', 'deg', 'deg*1e7', 'deg/s', - 'celcius', 'gauss', 'gauss/s', 'mgauss', 'mgauss^2', + 'celcius', 'gauss', 'gauss/s', 'gauss^2', 'hPa', 'kg', 'kg/m^2', 'kg m^2', 'mm', 'm', 'm/s', 'm^2', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad', 'Ohm', 'V', diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 3d798f59ef..6aa7aae2f2 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -149,9 +149,9 @@ private: hrt_abstime _last_magcal_us = 0; ///< last time the EKF was operating a mode that estimates magnetomer biases (uSec) hrt_abstime _total_cal_time_us = 0; ///< accumulated calibration time since the last save - float _last_valid_mag_cal[3] = {}; ///< last valid XYZ magnetometer bias estimates (mGauss) + float _last_valid_mag_cal[3] = {}; ///< last valid XYZ magnetometer bias estimates (Gauss) bool _valid_cal_available[3] = {}; ///< true when an unsaved valid calibration for the XYZ magnetometer bias is available - float _last_valid_variance[3] = {}; ///< variances for the last valid magnetometer XYZ bias estimates (mGauss**2) + float _last_valid_variance[3] = {}; ///< variances for the last valid magnetometer XYZ bias estimates (Gauss**2) // Used to control saving of mag declination to be used on next startup bool _mag_decl_saved = false; ///< true when the magnetic declination has been saved @@ -409,13 +409,13 @@ private: _param_ekf2_angerr_init, ///< 1-sigma tilt error after initial alignment using gravity vector (rad) // EKF saved XYZ magnetometer bias values - (ParamFloat) _param_ekf2_magbias_x, ///< X magnetometer bias (mGauss) - (ParamFloat) _param_ekf2_magbias_y, ///< Y magnetometer bias (mGauss) - (ParamFloat) _param_ekf2_magbias_z, ///< Z magnetometer bias (mGauss) + (ParamFloat) _param_ekf2_magbias_x, ///< X magnetometer bias (Gauss) + (ParamFloat) _param_ekf2_magbias_y, ///< Y magnetometer bias (Gauss) + (ParamFloat) _param_ekf2_magbias_z, ///< Z magnetometer bias (Gauss) (ParamInt) _param_ekf2_magbias_id, ///< ID of the magnetometer sensor used to learn the bias values (ParamFloat) - _param_ekf2_magb_vref, ///< Assumed error variance of previously saved magnetometer bias estimates (mGauss**2) + _param_ekf2_magb_vref, ///< Assumed error variance of previously saved magnetometer bias estimates (Gauss**2) (ParamFloat) _param_ekf2_magb_k, ///< maximum fraction of the learned magnetometer bias that is saved at each disarm diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index 4875726493..7f84af3653 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -1072,7 +1072,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_PITCH, 0.0f); * @reboot_required true * @volatile * @category system - * @unit mgauss + * @unit gauss * @decimal 3 */ PARAM_DEFINE_FLOAT(EKF2_MAGBIAS_X, 0.0f); @@ -1087,7 +1087,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAGBIAS_X, 0.0f); * @reboot_required true * @volatile * @category system - * @unit mgauss + * @unit gauss * @decimal 3 */ PARAM_DEFINE_FLOAT(EKF2_MAGBIAS_Y, 0.0f); @@ -1102,7 +1102,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAGBIAS_Y, 0.0f); * @reboot_required true * @volatile * @category system - * @unit mgauss + * @unit gauss * @decimal 3 */ PARAM_DEFINE_FLOAT(EKF2_MAGBIAS_Z, 0.0f); @@ -1122,7 +1122,7 @@ PARAM_DEFINE_INT32(EKF2_MAGBIAS_ID, 0); * * @group EKF2 * @reboot_required true - * @unit mgauss^2 + * @unit gauss^2 * @decimal 8 */ PARAM_DEFINE_FLOAT(EKF2_MAGB_VREF, 2.5E-7f);