Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL parameters documentation update #28053

Merged
merged 2 commits into from
Sep 11, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions Tools/autotest/param_metadata/param.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,13 +117,14 @@ def has_param(self, pname):
'dB' : 'decibel' ,
# compound

'kB' : 'kilobytes' ,
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
'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' ,
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
'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
Expand Down
13 changes: 0 additions & 13 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand All @@ -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",
Expand All @@ -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",
Expand All @@ -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",
Expand Down
54 changes: 51 additions & 3 deletions libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,14 @@ SIM *SIM::_singleton = nullptr;

// table of user settable parameters
const AP_Param::GroupInfo SIM::var_info[] = {


// @Param: DRIFT_SPEED
// @DisplayName: Gyro drift speed
// @Description: Gyro drift rate of change in degrees/second/minute
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are these really in minutes?! That's rather odd. Not saying you're wrong, but please make sure its right!

Also, we can put units into separate fields, like this:

Suggested change
// @Description: Gyro drift rate of change in degrees/second/minute
// @Description: Gyro drift rate of change
// @Units: deg/s/s

Known units are here: https://github.com/ardupilot/ardupilot/blob/master/Tools/autotest/param_metadata/param.py#L66

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It is indeed uncommon. I referred to the SITL.h where the comment states: AP_Float drift_speed; // degrees/second/minute
Also, I see double minutes = fmod(AP_HAL::micros64() / 60.0e6, period); if (minutes < period/2) { return minutes * ToRad(sitl->drift_speed); } return (period - minutes) * ToRad(sitl->drift_speed);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great, thanks!

Sometimes the hard-to-believe things just make you do more work :-)

AP_GROUPINFO("DRIFT_SPEED", 5, SIM, drift_speed, 0.05f),
// @Param: DRIFT_TIME
// @DisplayName: Gyro drift time
// @Description: Gyro drift duration of one full drift cycle (period in minutes)
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
AP_GROUPINFO("DRIFT_TIME", 6, SIM, drift_time, 5),
// @Param: ENGINE_MUL
// @DisplayName: Engine failure thrust scaler
Expand Down Expand Up @@ -111,6 +117,11 @@ const AP_Param::GroupInfo SIM::var_info[] = {
// @Units: V
// @User: Advanced
AP_GROUPINFO("BATT_VOLTAGE", 19, SIM, batt_voltage, 12.6f),
// @Param: BATT_CAP_AH
// @DisplayName: Simulated battery capacity
// @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),
AP_GROUPINFO("SONAR_RND", 24, SIM, sonar_noise, 0),
Expand Down Expand Up @@ -168,10 +179,25 @@ const AP_Param::GroupInfo SIM::var_info[] = {
// @Description: Opflow data delay
// @Units: ms
AP_GROUPINFO("FLOW_DELAY", 36, SIM, flow_delay, 0),
// @Param: ADSB_COUNT
// @DisplayName: Number of ADSB 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
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
// @Description: Simulated standard deviation of radius in ADSB of another aircraft
// @Units: m
AP_GROUPINFO("ADSB_RADIUS", 46, SIM, adsb_radius_m, 10000),
// @Param: ADSB_ALT
// @DisplayName: ADSB altitude of another aircraft
// @Description: Simulated ADSB altitude of another aircraft
// @Units: m
AP_GROUPINFO("ADSB_ALT", 47, SIM, adsb_altitude_m, 1000),
AP_GROUPINFO("PIN_MASK", 50, SIM, pin_mask, 0),
// @Param: ADSB_TX
// @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),
// @Param: SPEEDUP
// @DisplayName: Sim Speedup
Expand Down Expand Up @@ -261,7 +287,9 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
// @Path: ./SIM_Parachute.cpp
AP_SUBGROUPINFO(parachute_sim, "PARA_", 27, SIM, Parachute),

// enable bandwidth limitting on telemetry ports:
// @Param: BAUDLIMIT_EN
// @DisplayName: Telemetry bandwidth limitting
// @Description: SITL enable bandwidth limitting on telemetry ports with non-zero values
AP_GROUPINFO("BAUDLIMIT_EN", 28, SIM, telem_baudlimit_enable, 0),

// @Group: PLD_
Expand Down Expand Up @@ -327,6 +355,10 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
// @Path: ./SIM_ToneAlarm.cpp
AP_SUBGROUPINFO(tonealarm_sim, "TA_", 57, SIM, ToneAlarm),

// @Param: EFI_TYPE
// @DisplayName: Type of Electronic Fuel Injection
// @Description: Different types of Electronic Fuel Injection (EFI) systems
// @Values: 0:None,1:MegaSquirt EFI system, 2:Löweheiser EFI system, 8:Hirth engines
AP_GROUPINFO("EFI_TYPE", 58, SIM, efi_type, SIM::EFI_TYPE_NONE),

// 59 was SAFETY_STATE
Expand Down Expand Up @@ -468,6 +500,10 @@ const AP_Param::GroupInfo SIM::var_info3[] = {
AP_SUBGROUPINFO(ie24_sim, "IE24_", 32, SIM, IntelligentEnergy24),

// user settable barometer parameters

// @Param: BARO_COUNT
// @DisplayName: Baro count
// @Description: Total baro count
AP_GROUPINFO("BARO_COUNT", 33, SIM, baro_count, 2),

AP_SUBGROUPINFO(baro[0], "BARO_", 34, SIM, SIM::BaroParm),
Expand Down Expand Up @@ -525,6 +561,10 @@ const AP_Param::GroupInfo SIM::var_info3[] = {
// @User: Advanced
AP_GROUPINFO("ESC_TELEM", 40, SIM, esc_telem, 1),

// @Param: ESC_ARM_RPM
// @DisplayName: ESC RPM when armed
// @Description: Simulated RPM when motors are armed
// @User: Advanced
AP_GROUPINFO("ESC_ARM_RPM", 41, SIM, esc_rpm_armed, 0.0f),

// @Param: UART_LOSS
Expand Down Expand Up @@ -1043,8 +1083,16 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @Description: channels which are passed through to actual hardware when running sim on actual hardware
AP_GROUPINFO("OH_MASK", 28, SIM, on_hardware_output_enable_mask, 0),
#if AP_SIM_INS_FILE_ENABLED
// read and write IMU data to/from files

// @Param: GYR_FILE_RW
// @DisplayName: Gyro data to/from files
// @Description: Read and write gyro data to/from files
// @Values: 0:Stop writing data, 1:Read data from file, 2:Write data to a file, 3: Read data from file and stop on EOF
AP_GROUPINFO("GYR_FILE_RW", 29, SIM, gyro_file_rw, INSFileMode::INS_FILE_NONE),
// @Param: ACC_FILE_RW
// @DisplayName: Accelerometer data to/from files
// @Description: Read and write accelerometer data to/from files
// @Values: 0:Stop writing data, 1:Read data from file, 2:Write data to a file, 3: Read data from file and stop on EOF
AP_GROUPINFO("ACC_FILE_RW", 30, SIM, accel_file_rw, INSFileMode::INS_FILE_NONE),
#endif

Expand Down
Loading