mirror of https://github.com/ArduPilot/ardupilot
SITL:add SIM param metadata
This commit is contained in:
parent
a2b0bbffdb
commit
e96a55c1b6
|
@ -85,7 +85,7 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
|||
// @Param: RC_FAIL
|
||||
// @DisplayName: Simulated RC signal failure
|
||||
// @Description: Allows you to emulate rc failures in sim
|
||||
// @Values: 0:Disabled,1:No RC pusles,2:Binding pulses
|
||||
// @Values: 0:Disabled,1:No RC pusles,2:All Channels neutral except Throttle is 950us
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_FAIL", 25, SIM, rc_fail, 0),
|
||||
AP_GROUPINFO("FLOAT_EXCEPT", 28, SIM, float_exception, 1),
|
||||
|
@ -99,6 +99,11 @@ 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),
|
||||
AP_GROUPINFO("ADSB_TX", 51, SIM, adsb_tx, 0),
|
||||
// @Param: SPEEDUP
|
||||
// @DisplayName: Sim Speedup
|
||||
// @Description: Runs the simulation at multiples of normal speed. Do not use if realtime physics, like RealFlight, is being used
|
||||
// @Range: 1 10
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, -1),
|
||||
AP_GROUPINFO("IMU_POS", 53, SIM, imu_pos_offset, 0),
|
||||
AP_SUBGROUPEXTENSION("", 54, SIM, var_ins),
|
||||
|
@ -125,13 +130,22 @@ const AP_Param::GroupInfo SIM::var_info2[] = {
|
|||
AP_GROUPINFO("TEMP_BFACTOR", 4, SIM, temp_baro_factor, 0),
|
||||
|
||||
AP_GROUPINFO("WIND_DIR_Z", 10, SIM, wind_dir_z, 0),
|
||||
// @Param: WIND_T_
|
||||
// @DisplayName: Wind Profile Type
|
||||
// @Description: Selects how wind varies from surface to WIND_T_ALT
|
||||
// @Values: 0:square law,1: none, 2:linear-see WIND_T_COEF
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_T" ,15, SIM, wind_type, SIM::WIND_TYPE_SQRT),
|
||||
// @Param: WIND_T_ALT
|
||||
// @DisplayName: Full Wind Altitude
|
||||
// @Description: Altitude at which wind reaches full strength, rising from 0 at ground level
|
||||
// @Description: Altitude at which wind reaches full strength, decaying from full strength as altitude lowers to ground level
|
||||
// @Units: m
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_T_ALT" ,16, SIM, wind_type_alt, 60),
|
||||
// @Param: WIND_T_COEF
|
||||
// @DisplayName: Linear Wind Curve Coeff
|
||||
// @Description: For linear wind profile,wind is reduced by (Altitude-WIND_T_ALT) x this value
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_T_COEF", 17, SIM, wind_type_coef, 0.01f),
|
||||
AP_GROUPINFO("RC_CHANCOUNT",21, SIM, rc_chancount, 16),
|
||||
// @Group: SPR_
|
||||
|
@ -369,6 +383,11 @@ const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = {
|
|||
// user settable parameters for the 1st airspeed sensor
|
||||
AP_GROUPINFO("RND", 1, SIM::AirspeedParm, noise, 2.0),
|
||||
AP_GROUPINFO("OFS", 2, SIM::AirspeedParm, offset, 2013),
|
||||
// @Param: ARSPD_FAIL
|
||||
// @DisplayName: Airspeed sensor failure
|
||||
// @Description: Simulates Airspeed sensor 1 failure
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FAIL", 3, SIM::AirspeedParm, fail, 0),
|
||||
AP_GROUPINFO("FAILP", 4, SIM::AirspeedParm, fail_pressure, 0),
|
||||
AP_GROUPINFO("PITOT", 5, SIM::AirspeedParm, fail_pitot_pressure, 0),
|
||||
|
@ -380,6 +399,11 @@ const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = {
|
|||
#if HAL_SIM_GPS_ENABLED
|
||||
// GPS SITL parameters
|
||||
const AP_Param::GroupInfo SIM::var_gps[] = {
|
||||
// @Param: GPS_DISABLE
|
||||
// @DisplayName: GPS 1 disable
|
||||
// @Description: Disables GPS 1
|
||||
// @Values: 0:Enable, 1:GPS Disabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GPS_DISABLE", 1, SIM, gps_disable[0], 0),
|
||||
AP_GROUPINFO("GPS_LAG_MS", 2, SIM, gps_delay_ms[0], 100),
|
||||
AP_GROUPINFO("GPS_TYPE", 3, SIM, gps_type[0], GPS::Type::UBLOX),
|
||||
|
@ -395,7 +419,11 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
|
|||
AP_GROUPINFO("GPS_HDG", 13, SIM, gps_hdg_enabled[0], SIM::GPS_HEADING_NONE),
|
||||
AP_GROUPINFO("GPS_ACC", 14, SIM, gps_accuracy[0], 0.3),
|
||||
AP_GROUPINFO("GPS_VERR", 15, SIM, gps_vel_err[0], 0),
|
||||
|
||||
// @Param: GPS2_DISABLE
|
||||
// @DisplayName: GPS 2 disable
|
||||
// @Description: Disables GPS 2
|
||||
// @Values: 0:Enable, 1:GPS Disabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GPS2_DISABLE", 30, SIM, gps_disable[1], 1),
|
||||
AP_GROUPINFO("GPS2_LAG_MS", 31, SIM, gps_delay_ms[1], 100),
|
||||
AP_GROUPINFO("GPS2_TYPE", 32, SIM, gps_type[1], GPS::Type::UBLOX),
|
||||
|
@ -454,12 +482,22 @@ const AP_Param::GroupInfo SIM::var_mag[] = {
|
|||
#if MAX_CONNECTED_MAGS > 7
|
||||
AP_GROUPINFO("MAG8_DEVID", 18, SIM, mag_devid[7], 0),
|
||||
#endif
|
||||
// @Param: MAG1_FAIL
|
||||
// @DisplayName: MAG1 Failure
|
||||
// @Description: Simulated failure of MAG1
|
||||
// @Values: 0:Disabled, 1:MAG1 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAG1_FAIL", 26, SIM, mag_fail[0], 0),
|
||||
#if HAL_COMPASS_MAX_SENSORS > 1
|
||||
AP_GROUPINFO("MAG2_OFS", 19, SIM, mag_ofs[1], 0),
|
||||
AP_GROUPINFO("MAG2_DIA", 20, SIM, mag_diag[1], 0),
|
||||
AP_GROUPINFO("MAG2_ODI", 21, SIM, mag_offdiag[1], 0),
|
||||
AP_GROUPINFO("MAG2_ORIENT", 22, SIM, mag_orient[1], 0),
|
||||
// @Param: MAG2_FAIL
|
||||
// @DisplayName: MAG2 Failure
|
||||
// @Description: Simulated failure of MAG2
|
||||
// @Values: 0:Disabled, 1:MAG2 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAG2_FAIL", 27, SIM, mag_fail[1], 0),
|
||||
AP_GROUPINFO("MAG2_SCALING", 28, SIM, mag_scaling[1], 1),
|
||||
#endif
|
||||
|
@ -467,6 +505,11 @@ const AP_Param::GroupInfo SIM::var_mag[] = {
|
|||
AP_GROUPINFO("MAG3_OFS", 23, SIM, mag_ofs[2], 0),
|
||||
AP_GROUPINFO("MAG3_DIA", 24, SIM, mag_diag[2], 0),
|
||||
AP_GROUPINFO("MAG3_ODI", 25, SIM, mag_offdiag[2], 0),
|
||||
// @Param: MAG3_FAIL
|
||||
// @DisplayName: MAG3 Failure
|
||||
// @Description: Simulated failure of MAG3
|
||||
// @Values: 0:Disabled, 1:MAG3 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAG3_FAIL", 29, SIM, mag_fail[2], 0),
|
||||
AP_GROUPINFO("MAG3_SCALING", 30, SIM, mag_scaling[2], 1),
|
||||
AP_GROUPINFO("MAG3_ORIENT", 36, SIM, mag_orient[2], 0),
|
||||
|
@ -525,14 +568,39 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
|
|||
#if INS_MAX_INSTANCES > 2
|
||||
AP_GROUPINFO("GYR3_SCALE", 16, SIM, gyro_scale[2], 0),
|
||||
#endif
|
||||
// @Param: ACCEL1_FAIL
|
||||
// @DisplayName: ACCEL1 Failure
|
||||
// @Description: Simulated failure of ACCEL1
|
||||
// @Values: 0:Disabled, 1:ACCEL1 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACCEL1_FAIL", 17, SIM, accel_fail[0], 0),
|
||||
#if INS_MAX_INSTANCES > 1
|
||||
// @Param: ACCEL2_FAIL
|
||||
// @DisplayName: ACCEL2 Failure
|
||||
// @Description: Simulated failure of ACCEL2
|
||||
// @Values: 0:Disabled, 1:ACCEL2 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACCEL2_FAIL", 18, SIM, accel_fail[1], 0),
|
||||
#endif
|
||||
#if INS_MAX_INSTANCES > 2
|
||||
// @Param: ACCEL3_FAIL
|
||||
// @DisplayName: ACCEL3 Failure
|
||||
// @Description: Simulated failure of ACCEL3
|
||||
// @Values: 0:Disabled, 1:ACCEL3 Failure
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACCEL3_FAIL", 19, SIM, accel_fail[2], 0),
|
||||
#endif
|
||||
// @Param: GYRO_FAIL_MSK
|
||||
// @DisplayName: Gyro Failure Mask
|
||||
// @Description: Determines if the gyro reading updates are stopped when for an IMU simulated failure by ACCELx_FAIL params
|
||||
// @Values: 0:Disabled, 1:Readings stopped
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("GYR_FAIL_MSK", 20, SIM, gyro_fail_mask, 0),
|
||||
// @Param: ACC_FAIL_MSK
|
||||
// @DisplayName: Accelerometer Failure Mask
|
||||
// @Description: Determines if the acclerometer reading updates are stopped when for an IMU simulated failure by ACCELx_FAIL params
|
||||
// @Values: 0:Disabled, 1:Readings stopped
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ACC_FAIL_MSK", 21, SIM, accel_fail_mask, 0),
|
||||
AP_GROUPINFO("ACC1_SCAL", 22, SIM, accel_scale[0], 0),
|
||||
#if INS_MAX_INSTANCES > 1
|
||||
|
|
Loading…
Reference in New Issue