From 46763d61c6742f14cf7aa983a20a4bcc9af27993 Mon Sep 17 00:00:00 2001 From: Yuxin Pan <0@outlook.it> Date: Mon, 9 Sep 2024 18:43:48 -0700 Subject: [PATCH] SITL: add some parameter documentation SITL: vehicle_test_suite.py parameters removal from whitelist SITL: Add known unit amp hour SITL: Add known unit Ah Co-authored-by: Peter Barker --- Tools/autotest/param_metadata/param.py | 5 +++-- Tools/autotest/vehicle_test_suite.py | 13 ------------- libraries/SITL/SITL.cpp | 7 ++++--- 3 files changed, 7 insertions(+), 18 deletions(-) diff --git a/Tools/autotest/param_metadata/param.py b/Tools/autotest/param_metadata/param.py index 89e0294e8fa05f..976e811f53b083 100644 --- a/Tools/autotest/param_metadata/param.py +++ b/Tools/autotest/param_metadata/param.py @@ -117,13 +117,14 @@ def has_param(self, pname): 'dB' : 'decibel' , # compound - 'kB' : 'kilobytes' , + 'kB' : 'kilobytes' , 'MB' : 'megabyte' , 'm.m/s/s' : 'square meter per square second', 'deg/m/s' : 'degrees per meter per second' , 'm/s/m' : 'meters per second per meter' , # Why not use Hz here ???? 'mGauss/A': 'milligauss per ampere' , - 'mAh' : 'milliampere hour' , + 'mAh' : 'milliampere hour' , + 'Ah' : 'ampere hour' , 'A/V' : 'ampere per volt' , 'm/V' : 'meters per volt' , 'gravities': 'standard acceleration due to gravity' , # g_n would be a more correct unit, but IMHO no one understands what g_n means diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index cffa714ce99497..aab4f587527120 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -2559,14 +2559,9 @@ def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None): def get_sim_parameter_documentation_get_whitelist(self): # common parameters ret = set([ - "SIM_ACC_FILE_RW", "SIM_ACC_TRIM_X", "SIM_ACC_TRIM_Y", "SIM_ACC_TRIM_Z", - "SIM_ADSB_ALT", - "SIM_ADSB_COUNT", - "SIM_ADSB_RADIUS", - "SIM_ADSB_TX", "SIM_ARSPD2_OFS", "SIM_ARSPD2_RND", "SIM_ARSPD_OFS", @@ -2591,7 +2586,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_BAR3_WCF_LFT", "SIM_BAR3_WCF_RGT", "SIM_BAR3_WCF_UP", - "SIM_BARO_COUNT", "SIM_BARO_DELAY", "SIM_BARO_DISABLE", "SIM_BARO_FREEZE", @@ -2601,12 +2595,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_BARO_WCF_LFT", "SIM_BARO_WCF_RGT", "SIM_BARO_WCF_UP", - "SIM_BATT_CAP_AH", - "SIM_BAUDLIMIT_EN", - "SIM_DRIFT_SPEED", - "SIM_DRIFT_TIME", - "SIM_EFI_TYPE", - "SIM_ESC_ARM_RPM", "SIM_FTOWESC_ENA", "SIM_FTOWESC_POW", "SIM_GND_BEHAV", @@ -2616,7 +2604,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_GYR4_RND", "SIM_GYR5_RND", "SIM_GYR_FAIL_MSK", - "SIM_GYR_FILE_RW", "SIM_IE24_ENABLE", "SIM_IE24_ERROR", "SIM_IE24_STATE", diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 7362fac9b916b9..6d85b5059d7064 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -119,7 +119,8 @@ const AP_Param::GroupInfo SIM::var_info[] = { AP_GROUPINFO("BATT_VOLTAGE", 19, SIM, batt_voltage, 12.6f), // @Param: BATT_CAP_AH // @DisplayName: Simulated battery capacity - // @Description: Simulated battery capacity in Amp hours + // @Description: Simulated battery capacity + // @Units: Ah // @User: Advanced AP_GROUPINFO("BATT_CAP_AH", 20, SIM, batt_capacity_ah, 0), AP_GROUPINFO("SONAR_GLITCH", 23, SIM, sonar_glitch, 0), @@ -180,7 +181,7 @@ const AP_Param::GroupInfo SIM::var_info[] = { AP_GROUPINFO("FLOW_DELAY", 36, SIM, flow_delay, 0), // @Param: ADSB_COUNT // @DisplayName: Number of ADSB aircrafts - // @Description: Total number of ADSB simulated aircrafts + // @Description: Total number of ADSB simulated aircraft AP_GROUPINFO("ADSB_COUNT", 45, SIM, adsb_plane_count, -1), // @Param: ADSB_RADIUS // @DisplayName: ADSB radius stddev of another aircraft @@ -194,7 +195,7 @@ const AP_Param::GroupInfo SIM::var_info[] = { AP_GROUPINFO("ADSB_ALT", 47, SIM, adsb_altitude_m, 1000), AP_GROUPINFO("PIN_MASK", 50, SIM, pin_mask, 0), // @Param: ADSB_TX - // @DisplayName: ADSB transceiever enable + // @DisplayName: ADSB transmit enable // @Description: ADSB transceiever enable and disable // @Values: 0:Transceiever disable, 1:Transceiever enable AP_GROUPINFO("ADSB_TX", 51, SIM, adsb_tx, 0),