diff --git a/src/drivers/heater/heater_params.c b/src/drivers/heater/heater_params.c
index ff824ad116..8dfb5256f4 100644
--- a/src/drivers/heater/heater_params.c
+++ b/src/drivers/heater/heater_params.c
@@ -53,7 +53,7 @@ PARAM_DEFINE_INT32(SENS_TEMP_ID, 0);
*
* @category system
* @group Sensors
- * @unit C
+ * @unit celcius
* @min 0
* @max 85.0
* @decimal 3
@@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(SENS_IMU_TEMP, 55.0f);
*
* @category system
* @group Sensors
- * @unit microseconds/C
+ * @unit us/C
* @min 0
* @max 1.0
* @decimal 3
@@ -77,7 +77,7 @@ PARAM_DEFINE_FLOAT(SENS_IMU_TEMP_I, 0.025f);
*
* @category system
* @group Sensors
- * @unit microseconds/C
+ * @unit us/C
* @min 0
* @max 2.0
* @decimal 3
diff --git a/src/drivers/power_monitor/ina226/ina226_params.c b/src/drivers/power_monitor/ina226/ina226_params.c
index b97a7baf08..8049a3f949 100644
--- a/src/drivers/power_monitor/ina226/ina226_params.c
+++ b/src/drivers/power_monitor/ina226/ina226_params.c
@@ -36,7 +36,6 @@
* INA226 Power Monitor Config
*
* @group Sensors
- * @unit u
* @min 0
* @max 65535
* @decimal 1
diff --git a/src/lib/battery/battery_params_deprecated.c b/src/lib/battery/battery_params_deprecated.c
index 0544227857..d180552534 100644
--- a/src/lib/battery/battery_params_deprecated.c
+++ b/src/lib/battery/battery_params_deprecated.c
@@ -95,7 +95,7 @@ PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.3f);
* BAT_V_LOAD_DROP for all calculations.
*
* @group Battery Calibration
- * @unit Ohms
+ * @unit Ohm
* @min -1.0
* @max 0.2
* @reboot_required true
diff --git a/src/lib/collision_prevention/collisionprevention_params.c b/src/lib/collision_prevention/collisionprevention_params.c
index 3f80cf84bf..18adca0ac0 100644
--- a/src/lib/collision_prevention/collisionprevention_params.c
+++ b/src/lib/collision_prevention/collisionprevention_params.c
@@ -46,7 +46,7 @@
*
* @min -1
* @max 15
- * @unit meters
+ * @unit m
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(CP_DIST, -1.0f);
@@ -58,7 +58,7 @@ PARAM_DEFINE_FLOAT(CP_DIST, -1.0f);
*
* @min 0
* @max 1
- * @unit seconds
+ * @unit s
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(CP_DELAY, 0.4f);
@@ -70,7 +70,7 @@ PARAM_DEFINE_FLOAT(CP_DELAY, 0.4f);
*
* @min 0
* @max 90
- * @unit [deg]
+ * @unit deg
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(CP_GUIDE_ANG, 30.f);
diff --git a/src/lib/parameters/parameters_injected.xml b/src/lib/parameters/parameters_injected.xml
index 9347cf91ac..b927adc289 100644
--- a/src/lib/parameters/parameters_injected.xml
+++ b/src/lib/parameters/parameters_injected.xml
@@ -5,7 +5,7 @@
Speed controller bandwidth
Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.
- Hertz
+ Hz
10
250
@@ -24,7 +24,7 @@
decreased. Higher values result in faster response, but may result
in oscillation and excessive overshoot. Lower values result in a
slower, smoother response.
- amp-seconds per radian
+ C/rad
3
0.00
1.00
@@ -32,7 +32,7 @@
Idle speed (e Hz)
Idle speed (e Hz)
- Hertz
+ Hz
3
0.0
100.0
@@ -40,14 +40,13 @@
Spin-up rate (e Hz/s)
Spin-up rate (e Hz/s)
- Hz/s
+ 1/s^2
5
1000
Index of this ESC in throttle command messages.
Index of this ESC in throttle command messages.
- Index
0
15
@@ -60,14 +59,14 @@
Extended status interval (µs)
Extended status interval (µs)
- µs
+ us
0
1000000
ESC status interval (µs)
ESC status interval (µs)
- µs
+ us
1000000
@@ -78,7 +77,7 @@
the continuous current rating listed in the motor’s specification
sheet, or set equal to the motor’s specified continuous power
divided by the motor voltage limit.
- Amps
+ A
3
1
80
@@ -88,14 +87,14 @@
Motor Kv in RPM per volt. This can be taken from the motor’s
specification sheet; accuracy will help control performance but
some deviation from the specified value is acceptable.
- RPM/v
+ rpm/V
0
4000
READ ONLY: Motor inductance in henries.
READ ONLY: Motor inductance in henries. This is measured on start-up.
- henries
+ H
3
@@ -103,7 +102,6 @@
Number of motor poles. Used to convert mechanical speeds to
electrical speeds. This number should be taken from the motor’s
specification sheet.
- Poles
2
40
@@ -112,13 +110,13 @@
READ ONLY: Motor resistance in ohms. This is measured on start-up. When
tuning a new motor, check that this value is approximately equal
to the value shown in the motor’s specification sheet.
- Ohms
+ Ohm
3
Acceleration limit (V)
Acceleration limit (V)
- Volts
+ V
3
0.01
1.00
@@ -130,7 +128,7 @@
safely be above the nominal voltage of the motor; to determine the
actual motor voltage limit, divide the motor’s rated power by the
motor current limit.
- Volts
+ V
3
0
@@ -192,7 +190,7 @@
used in the GNSS solution is below this threshold. Zero
disables the feature
- microseconds
+ us
0
1000000
diff --git a/src/lib/parameters/px4params/srcparser.py b/src/lib/parameters/px4params/srcparser.py
index 3594906994..750e236d87 100644
--- a/src/lib/parameters/px4params/srcparser.py
+++ b/src/lib/parameters/px4params/srcparser.py
@@ -346,6 +346,21 @@ class SourceParser(object):
Validates the parameter meta data.
"""
seenParamNames = []
+ #allowedUnits should match set defined in /Firmware/validation/module_schema.yaml
+ allowedUnits = set ([
+ '%', 'Hz', 'mAh',
+ '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',
+ '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',
+ 'us', 'ms', 's',
+ 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad',
+ 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C',
+ 'N/(m/s)', 'Nm/(rad/s)', 'Nm', 'N',
+ 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD',''])
for group in self.GetParamGroups():
for param in group.GetParams():
name = param.GetName()
@@ -364,6 +379,10 @@ class SourceParser(object):
default = param.GetDefault()
min = param.GetFieldValue("min")
max = param.GetFieldValue("max")
+ units = param.GetFieldValue("unit")
+ if units not in allowedUnits:
+ sys.stderr.write("Invalid unit in {0}: {1}\n".format(name, units))
+ return False
#sys.stderr.write("{0} default:{1} min:{2} max:{3}\n".format(name, default, min, max))
if default != "" and not self.IsNumber(default):
sys.stderr.write("Default value not number: {0} {1}\n".format(name, default))
diff --git a/src/lib/systemlib/system_params.c b/src/lib/systemlib/system_params.c
index 44e09796f5..29e369e3e3 100644
--- a/src/lib/systemlib/system_params.c
+++ b/src/lib/systemlib/system_params.c
@@ -179,7 +179,7 @@ PARAM_DEFINE_INT32(SYS_CAL_BARO, 0);
* Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL.
* If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.
*
- * @unit deg C
+ * @unit celcius
* @min 10
* @group System
*/
@@ -190,7 +190,7 @@ PARAM_DEFINE_INT32(SYS_CAL_TDEL, 24);
*
* Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.
*
- * @unit deg C
+ * @unit celcius
* @group System
*/
PARAM_DEFINE_INT32(SYS_CAL_TMIN, 5);
@@ -200,7 +200,7 @@ PARAM_DEFINE_INT32(SYS_CAL_TMIN, 5);
*
* Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.
*
- * @unit deg C
+ * @unit celcius
* @group System
*/
PARAM_DEFINE_INT32(SYS_CAL_TMAX, 10);
diff --git a/src/lib/weather_vane/weathervane_params.c b/src/lib/weather_vane/weathervane_params.c
index 80905ff36e..2c98d53404 100644
--- a/src/lib/weather_vane/weathervane_params.c
+++ b/src/lib/weather_vane/weathervane_params.c
@@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(WV_EN, 0);
*
* @min 0.0
* @max 3.0
- * @unit 1/s
+ * @unit Hz
* @increment 0.01
* @decimal 3
* @group VTOL Attitude Control
diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c
index 030837e8eb..80ff09b16d 100644
--- a/src/modules/airspeed_selector/airspeed_selector_params.c
+++ b/src/modules/airspeed_selector/airspeed_selector_params.c
@@ -6,7 +6,7 @@
*
* @min 0
* @max 1
- * @unit m/s/s
+ * @unit m/s^2
* @group Airspeed Validator
*/
PARAM_DEFINE_FLOAT(ASPD_W_P_NOISE, 0.1f);
@@ -18,7 +18,7 @@ PARAM_DEFINE_FLOAT(ASPD_W_P_NOISE, 0.1f);
*
* @min 0
* @max 0.1
- * @unit 1/s
+ * @unit Hz
* @group Airspeed Validator
*/
PARAM_DEFINE_FLOAT(ASPD_SC_P_NOISE, 0.0001);
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index 0b038cc50b..dcc2ee4448 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -587,7 +587,7 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_GB, 0.0011f);
* Maximum accelerometer inconsistency between IMU units that will allow arming
*
* @group Commander
- * @unit m/s/s
+ * @unit m/s^2
* @min 0.1
* @max 1.0
* @decimal 2
@@ -703,7 +703,7 @@ PARAM_DEFINE_INT32(COM_ARM_AUTH_REQ, 0);
* This sets number of seconds that the position checks need to be failed before the failsafe will activate.
* The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used.
*
- * @unit sec
+ * @unit s
* @reboot_required true
* @group Commander
* @min 1
@@ -720,7 +720,7 @@ PARAM_DEFINE_INT32(COM_POS_FS_DELAY, 1);
* If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds.
* The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used.
*
- * @unit sec
+ * @unit s
* @reboot_required true
* @group Commander
* @min 1
diff --git a/src/modules/commander/failure_detector/failure_detector_params.c b/src/modules/commander/failure_detector/failure_detector_params.c
index 55ea9b3de4..1cdf726062 100644
--- a/src/modules/commander/failure_detector/failure_detector_params.c
+++ b/src/modules/commander/failure_detector/failure_detector_params.c
@@ -55,7 +55,7 @@
*
* @min 60
* @max 180
- * @unit degrees
+ * @unit deg
* @group Failure Detector
*/
PARAM_DEFINE_INT32(FD_FAIL_R, 60);
@@ -73,7 +73,7 @@ PARAM_DEFINE_INT32(FD_FAIL_R, 60);
*
* @min 60
* @max 180
- * @unit degrees
+ * @unit deg
* @group Failure Detector
*/
PARAM_DEFINE_INT32(FD_FAIL_P, 60);
@@ -123,7 +123,7 @@ PARAM_DEFINE_INT32(FD_EXT_ATS_EN, 0);
*
* External ATS is required by ASTM F3322-18.
*
- * @unit microseconds
+ * @unit us
* @decimal 2
*
* @group Failure Detector
diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c
index 78b9681c1f..de4db4e0f6 100644
--- a/src/modules/ekf2/ekf2_params.c
+++ b/src/modules/ekf2/ekf2_params.c
@@ -268,7 +268,7 @@ PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 1.5e-2f);
* @group EKF2
* @min 0.01
* @max 1.0
- * @unit m/s/s
+ * @unit m/s^2
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f);
@@ -279,7 +279,7 @@ PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f);
* @group EKF2
* @min 0.0
* @max 0.01
- * @unit rad/s**2
+ * @unit rad/s^2
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f);
@@ -290,7 +290,7 @@ PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f);
* @group EKF2
* @min 0.0
* @max 0.01
- * @unit m/s**3
+ * @unit m/s^3
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f);
@@ -301,7 +301,7 @@ PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f);
* @group EKF2
* @min 0.0
* @max 0.1
- * @unit Gauss/s
+ * @unit gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f);
@@ -312,7 +312,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f);
* @group EKF2
* @min 0.0
* @max 0.1
- * @unit Gauss/s
+ * @unit gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f);
@@ -323,7 +323,7 @@ PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f);
* @group EKF2
* @min 0.0
* @max 1.0
- * @unit m/s/s
+ * @unit m/s^2
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_WIND_NOISE, 1.0e-1f);
@@ -389,7 +389,7 @@ PARAM_DEFINE_FLOAT(EKF2_HEAD_NOISE, 0.3f);
* @group EKF2
* @min 0.001
* @max 1.0
- * @unit Gauss
+ * @unit gauss
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_NOISE, 5.0e-2f);
@@ -509,7 +509,7 @@ PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0);
* @group EKF2
* @min 0.0
* @max 5.0
- * @unit m/s**2
+ * @unit m/s^2
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_ACCLIM, 0.5f);
@@ -547,7 +547,7 @@ PARAM_DEFINE_FLOAT(EKF2_BARO_GATE, 5.0f);
* @group EKF2
* @min 0.0
* @max 10.0
- * @unit M
+ * @unit m
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GND_EFF_DZ, 0.0f);
@@ -560,7 +560,7 @@ PARAM_DEFINE_FLOAT(EKF2_GND_EFF_DZ, 0.0f);
* @group EKF2
* @min 0.0
* @max 5.0
- * @unit M
+ * @unit m
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GND_MAX_HGT, 0.5f);
@@ -666,7 +666,7 @@ PARAM_DEFINE_INT32(EKF2_TERR_MASK, 3);
* @group EKF2
* @min 500000
* @max 10000000
- * @unit uSec
+ * @unit us
*/
PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000);
@@ -1021,7 +1021,7 @@ PARAM_DEFINE_FLOAT(EKF2_TAU_POS, 0.25f);
* @group EKF2
* @min 0.0
* @max 0.2
- * @unit rad/sec
+ * @unit rad/s
* @reboot_required true
* @decimal 2
*/
@@ -1033,7 +1033,7 @@ PARAM_DEFINE_FLOAT(EKF2_GBIAS_INIT, 0.1f);
* @group EKF2
* @min 0.0
* @max 0.5
- * @unit m/s/s
+ * @unit m/s^2
* @reboot_required true
* @decimal 2
*/
@@ -1072,7 +1072,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_PITCH, 0.0f);
* @reboot_required true
* @volatile
* @category system
- * @unit mGauss
+ * @unit mgauss
* @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 mgauss
* @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 mgauss
* @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 mgauss^2
* @decimal 8
*/
PARAM_DEFINE_FLOAT(EKF2_MAGB_VREF, 2.5E-7f);
@@ -1226,7 +1226,7 @@ PARAM_DEFINE_FLOAT(EKF2_EVP_GATE, 5.0f);
* @group EKF2
* @min 0.5
* @max 10.0
- * @unit (m/sec**2)**2
+ * @unit (m/s^2)^2
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f);
@@ -1238,7 +1238,7 @@ PARAM_DEFINE_FLOAT(EKF2_DRAG_NOISE, 2.5f);
* @group EKF2
* @min 1.0
* @max 100.0
- * @unit kg/m**2
+ * @unit kg/m^2
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 25.0f);
@@ -1250,7 +1250,7 @@ PARAM_DEFINE_FLOAT(EKF2_BCOEF_X, 25.0f);
* @group EKF2
* @min 1.0
* @max 100.0
- * @unit kg/m**2
+ * @unit kg/m^2
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_BCOEF_Y, 25.0f);
@@ -1331,7 +1331,7 @@ PARAM_DEFINE_FLOAT(EKF2_PCOEF_Z, 0.0f);
* @group EKF2
* @min 0.0
* @max 0.8
- * @unit m/s/s
+ * @unit m/s^2
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_ABL_LIM, 0.4f);
@@ -1344,7 +1344,7 @@ PARAM_DEFINE_FLOAT(EKF2_ABL_LIM, 0.4f);
* @group EKF2
* @min 20.0
* @max 200.0
- * @unit m/s/s
+ * @unit m/s^2
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_ABL_ACCLIM, 25.0f);
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index 9cd96e5393..9646d63d9a 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -617,7 +617,7 @@ PARAM_DEFINE_INT32(FW_BAT_SCALE_EN, 0);
*
* @min 45
* @max 720
- * @unit degrees
+ * @unit deg
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_ACRO_X_MAX, 90);
@@ -630,7 +630,7 @@ PARAM_DEFINE_FLOAT(FW_ACRO_X_MAX, 90);
*
* @min 45
* @max 720
- * @unit degrees
+ * @unit deg
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_ACRO_Y_MAX, 90);
@@ -643,7 +643,7 @@ PARAM_DEFINE_FLOAT(FW_ACRO_Y_MAX, 90);
*
* @min 10
* @max 180
- * @unit degrees
+ * @unit deg
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_ACRO_Z_MAX, 45);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index bac1dc1e6a..ab45c9413f 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -592,7 +592,7 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
* allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 1.0
* @max 10.0
* @decimal 1
diff --git a/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c b/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c
index dd883e04ad..1575cd09b2 100644
--- a/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c
+++ b/src/modules/fw_pos_control_l1/launchdetection/launchdetection_params.c
@@ -57,7 +57,7 @@ PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
*
* LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 0
* @decimal 1
* @increment 0.5
diff --git a/src/modules/local_position_estimator/params.c b/src/modules/local_position_estimator/params.c
index c6a78446a8..9c0c83009c 100644
--- a/src/modules/local_position_estimator/params.c
+++ b/src/modules/local_position_estimator/params.c
@@ -28,7 +28,7 @@ PARAM_DEFINE_FLOAT(LPE_FLW_SCALE, 1.3f);
* Optical flow rotation (roll/pitch) noise gain
*
* @group Local Position Estimator
- * @unit m/s / (rad)
+ * @unit m/s/rad
* @min 0.1
* @max 10.0
* @decimal 3
@@ -39,7 +39,7 @@ PARAM_DEFINE_FLOAT(LPE_FLW_R, 7.0f);
* Optical flow angular velocity noise gain
*
* @group Local Position Estimator
- * @unit m/s / (rad/s)
+ * @unit m/rad
* @min 0.0
* @max 10.0
* @decimal 3
@@ -143,7 +143,7 @@ PARAM_DEFINE_FLOAT(LPE_BAR_Z, 3.0f);
* GPS delay compensaton
*
* @group Local Position Estimator
- * @unit sec
+ * @unit s
* @min 0
* @max 0.4
* @decimal 2
@@ -224,7 +224,7 @@ PARAM_DEFINE_FLOAT(LPE_EPV_MAX, 5.0f);
* Set to zero to enable automatic compensation from measurement timestamps
*
* @group Local Position Estimator
- * @unit sec
+ * @unit s
* @min 0
* @max 0.1
* @decimal 2
@@ -285,7 +285,7 @@ PARAM_DEFINE_FLOAT(LPE_PN_P, 0.1f);
* Decrease to trust model more.
*
* @group Local Position Estimator
- * @unit (m/s)/s/sqrt(Hz)
+ * @unit m/s^2/sqrt(Hz)
* @min 0
* @max 1
* @decimal 8
@@ -296,7 +296,7 @@ PARAM_DEFINE_FLOAT(LPE_PN_V, 0.1f);
* Accel bias propagation noise density
*
* @group Local Position Estimator
- * @unit (m/s^2)/s/sqrt(Hz)
+ * @unit m/s^3/sqrt(Hz)
* @min 0
* @max 1
* @decimal 8
@@ -307,7 +307,7 @@ PARAM_DEFINE_FLOAT(LPE_PN_B, 1e-3f);
* Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)
*
* @group Local Position Estimator
- * @unit (m/s)/(sqrt(hz))
+ * @unit m/s/sqrt(Hz)
* @min 0
* @max 1
* @decimal 3
diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c
index 9c4148c1e0..6ac8fd1479 100644
--- a/src/modules/mc_att_control/mc_att_control_params.c
+++ b/src/modules/mc_att_control/mc_att_control_params.c
@@ -44,7 +44,7 @@
*
* Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
- * @unit 1/s
+ * @unit Hz
* @min 0.0
* @max 12
* @decimal 2
@@ -58,7 +58,7 @@ PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.5f);
*
* Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
- * @unit 1/s
+ * @unit Hz
* @min 0.0
* @max 12
* @decimal 2
@@ -72,7 +72,7 @@ PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f);
*
* Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
*
- * @unit 1/s
+ * @unit Hz
* @min 0.0
* @max 5
* @decimal 2
@@ -91,7 +91,7 @@ PARAM_DEFINE_FLOAT(MC_YAW_P, 2.8f);
*
* For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain.
*
- * @unit 1/s
+ * @unit Hz
* @min 0.0
* @max 1.0
* @decimal 2
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
index f46cda4053..0b7a7cdba5 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -465,7 +465,7 @@ PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f);
*
* Maximum deceleration for MPC_POS_MODE 1. Maximum acceleration and deceleration for MPC_POS_MODE 3.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 2.0
* @max 15.0
* @increment 1
@@ -479,7 +479,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.0f);
*
* Note: In manual, this parameter is only used in MPC_POS_MODE 1.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 2.0
* @max 15.0
* @increment 1
@@ -494,7 +494,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR, 3.0f);
*
* Note: This is only used when MPC_POS_MODE is set to 1.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 0.5
* @max 10.0
* @increment 1
@@ -506,7 +506,7 @@ PARAM_DEFINE_FLOAT(MPC_DEC_HOR_SLOW, 5.0f);
/**
* Maximum vertical acceleration in velocity controlled modes upward
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 2.0
* @max 15.0
* @increment 1
@@ -518,7 +518,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_UP_MAX, 4.0f);
/**
* Maximum vertical acceleration in velocity controlled modes down
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 2.0
* @max 15.0
* @increment 1
@@ -538,7 +538,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_DOWN_MAX, 3.0f);
*
* Note: This is only used when MPC_POS_MODE is set to a smoothing mode 1 or 3.
*
- * @unit m/s/s/s
+ * @unit m/s^3
* @min 0.5
* @max 500.0
* @increment 1
@@ -561,7 +561,7 @@ PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.0f);
*
* Note: This is only used when MPC_POS_MODE is set to 1.
*
- * @unit m/s/s/s
+ * @unit m/s^3
* @min 0
* @max 30.0
* @increment 1
@@ -577,7 +577,7 @@ PARAM_DEFINE_FLOAT(MPC_JERK_MIN, 8.0f);
* A lower value leads to smoother vehicle motions, but it also limits its
* agility.
*
- * @unit m/s/s/s
+ * @unit m/s^3
* @min 1.0
* @max 80.0
* @increment 1
diff --git a/src/modules/navigator/follow_target_params.c b/src/modules/navigator/follow_target_params.c
index 23c206b8f3..facfc9732e 100644
--- a/src/modules/navigator/follow_target_params.c
+++ b/src/modules/navigator/follow_target_params.c
@@ -48,7 +48,7 @@
*
* The minimum height in meters relative to home for following a target
*
- * @unit meters
+ * @unit m
* @min 8.0
* @group Follow target
*/
@@ -59,7 +59,7 @@ PARAM_DEFINE_FLOAT(NAV_MIN_FT_HT, 8.0f);
*
* The distance in meters to follow the target at
*
- * @unit meters
+ * @unit m
* @min 1.0
* @group Follow target
*/
@@ -70,7 +70,6 @@ PARAM_DEFINE_FLOAT(NAV_FT_DST, 8.0f);
*
* The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3)
*
- * @unit n/a
* @min 0
* @max 3
* @group Follow target
@@ -82,7 +81,6 @@ PARAM_DEFINE_INT32(NAV_FT_FS, 1);
* lower numbers increase the responsiveness to changing long lat
* but also ignore less noise
*
- * @unit n/a
* @min 0.0
* @max 1.0
* @decimal 2
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 19405d42cb..b3f7678caa 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -159,7 +159,7 @@ PARAM_DEFINE_FLOAT(NAV_TRAFF_A_RADU, 10);
*
* Latitude of airfield home waypoint
*
- * @unit deg * 1e7
+ * @unit deg*1e7
* @min -900000000
* @max 900000000
* @group Data Link Loss
@@ -171,7 +171,7 @@ PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810);
*
* Longitude of airfield home waypoint
*
- * @unit deg * 1e7
+ * @unit deg*1e7
* @min -1800000000
* @max 1800000000
* @group Data Link Loss
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
index a3bf36de27..fa097b6860 100644
--- a/src/modules/navigator/rtl_params.c
+++ b/src/modules/navigator/rtl_params.c
@@ -123,7 +123,7 @@ PARAM_DEFINE_INT32(RTL_TYPE, 0);
* Defines the half-angle of a cone centered around the destination position that
* affects the altitude at which the vehicle returns.
*
- * @unit degrees
+ * @unit deg
* @min 0
* @max 90
* @value 0 No cone, always climb to RTL_RETURN_ALT above destination.
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 1e2de63ff1..7afd7bcd9f 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(CAL_AIR_CMODEL, 0);
*
* @min 0.01
* @max 2.00
- * @unit meter
+ * @unit m
*
* @group Sensors
*/
@@ -70,7 +70,7 @@ PARAM_DEFINE_FLOAT(CAL_AIR_TUBELEN, 0.2f);
*
* @min 0.1
* @max 100
- * @unit millimeter
+ * @unit mm
*
* @group Sensors
*/
diff --git a/src/modules/sih/sih_params.c b/src/modules/sih/sih_params.c
index 72004439eb..1d0762b54c 100644
--- a/src/modules/sih/sih_params.c
+++ b/src/modules/sih/sih_params.c
@@ -58,7 +58,7 @@ PARAM_DEFINE_FLOAT(SIH_MASS, 1.0f);
* The intertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @min 0.0
* @decimal 3
* @increment 0.005
@@ -72,7 +72,7 @@ PARAM_DEFINE_FLOAT(SIH_IXX, 0.025f);
* The intertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @min 0.0
* @decimal 3
* @increment 0.005
@@ -86,7 +86,7 @@ PARAM_DEFINE_FLOAT(SIH_IYY, 0.025f);
* The intertia is a 3 by 3 symmetric matrix.
* It represents the difficulty of the vehicle to modify its angular rate.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @min 0.0
* @decimal 3
* @increment 0.005
@@ -100,7 +100,7 @@ PARAM_DEFINE_FLOAT(SIH_IZZ, 0.030f);
* The intertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @decimal 3
* @increment 0.005
* @group Simulation In Hardware
@@ -113,7 +113,7 @@ PARAM_DEFINE_FLOAT(SIH_IXY, 0.0f);
* The intertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @decimal 3
* @increment 0.005
* @group Simulation In Hardware
@@ -126,7 +126,7 @@ PARAM_DEFINE_FLOAT(SIH_IXZ, 0.0f);
* The intertia is a 3 by 3 symmetric matrix.
* This value can be set to 0 for a quad symmetric about its center of mass.
*
- * @unit kg*m*m
+ * @unit kg m^2
* @decimal 3
* @increment 0.005
* @group Simulation In Hardware
@@ -240,7 +240,7 @@ PARAM_DEFINE_FLOAT(SIH_KDW, 0.025f);
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
- * @unit 1e-7 deg
+ * @unit deg*1e7
* @min -850000000
* @max 850000000
* @group Simulation In Hardware
@@ -256,7 +256,7 @@ PARAM_DEFINE_INT32(SIH_LOC_LAT0, 454671160);
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
- * @unit 1e-7 deg
+ * @unit deg*1e7
* @min -1800000000
* @max 1800000000
* @group Simulation In Hardware
@@ -295,7 +295,7 @@ PARAM_DEFINE_FLOAT(SIH_LOC_H0, 32.34f);
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
- * @unit Gauss
+ * @unit gauss
* @min -1.0
* @max 1.0
* @decimal 2
@@ -315,7 +315,7 @@ PARAM_DEFINE_FLOAT(SIH_LOC_MU_X, 0.179f);
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
- * @unit Gauss
+ * @unit gauss
* @min -1.0
* @max 1.0
* @decimal 2
@@ -335,7 +335,7 @@ PARAM_DEFINE_FLOAT(SIH_LOC_MU_Y, -0.045f);
* LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others
* to represent a physical ground location on Earth.
*
- * @unit Gauss
+ * @unit gauss
* @min -1.0
* @max 1.0
* @decimal 2
diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c
index e3251524e1..03ab1e6024 100644
--- a/src/modules/vtol_att_control/vtol_att_control_params.c
+++ b/src/modules/vtol_att_control/vtol_att_control_params.c
@@ -151,7 +151,7 @@ PARAM_DEFINE_FLOAT(VT_B_TRANS_THR, 0.0f);
* Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint.
* For standard vtol and tiltrotors a controller is used to track this value during the transition.
*
- * @unit m/s/s
+ * @unit m/s^2
* @min 0.5
* @max 10
* @increment 0.1
@@ -263,7 +263,7 @@ PARAM_DEFINE_INT32(VT_FW_QC_R, 0);
*
* The duration of the front transition when there is no airspeed feedback available.
*
- * @unit seconds
+ * @unit s
* @min 1.0
* @max 30.0
* @group VTOL Attitude Control
@@ -321,7 +321,7 @@ PARAM_DEFINE_FLOAT(VT_FW_DIFTHR_SC, 0.1f);
* Backtransition deceleration setpoint to pitch feedforward gain.
*
*
- * @unit rad*s*s/m
+ * @unit rad s^2/m
* @min 0
* @max 0.2
* @decimal 1
@@ -334,7 +334,7 @@ PARAM_DEFINE_FLOAT(VT_B_DEC_FF, 0.12f);
* Backtransition deceleration setpoint to pitch I gain.
*
*
- * @unit rad*s/m
+ * @unit rad s/m
* @min 0
* @max 0.3
* @decimal 1
diff --git a/validation/module_schema.yaml b/validation/module_schema.yaml
index 142724db63..6982daf66c 100644
--- a/validation/module_schema.yaml
+++ b/validation/module_schema.yaml
@@ -135,14 +135,18 @@ parameters:
type: string
allowed: [
'%', 'Hz', 'mAh',
- 'rad', '%/rad', 'rad/s',
+ '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',
- 'hPa', 'kg', 'kg/m^2',
- 'mm', 'm', 'm/s', 'm/s^2', 'm/s^3', 'm/s^2/sqrt(Hz)', 'm/s/rad',
+ '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',
- 'us', 'ms', 's' ]
+ 'us', 'ms', 's',
+ 'S', 'A/%', '(m/s^2)^2', 'm/m', 'tan(rad)^2', '(m/s)^2', 'm/rad',
+ 'm/s^3/sqrt(Hz)', 'm/s/sqrt(Hz)', 's/(1000*PWM)', '%m/s', 'min', 'us/C',
+ 'N/(m/s)', 'Nm/(rad/s)', 'Nm', 'N',
+ 'normalized_thrust/s', 'normalized_thrust', 'norm', 'SD']
bit:
# description of all bits for type bitmask.
# The first bit is 0.