SITL: document SITL GPS params

* Document GPS_LAG_MS

* Document GPS2_LAG_MS, Consistency fixes

* document DriftAlt & Hz

* document GPS_POS offsets

* document locktime and noise

* document GPS_ALT_OFS and GPS_HDG

* document GPS_ACC

* Finish documenting GPS parameters
This commit is contained in:
Anthony Luo 2023-09-02 16:59:26 -04:00 committed by Andrew Tridgell
parent d8eafc7a51
commit 6201f56d40
1 changed files with 118 additions and 0 deletions

View File

@ -462,6 +462,11 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Values: 0:Enable, 1:GPS Disabled
// @User: Advanced
AP_GROUPINFO("GPS_DISABLE", 1, SIM, gps_disable[0], 0),
// @Param: GPS_LAG_MS
// @DisplayName: GPS 1 Lag
// @Description: GPS 1 lag
// @Units: ms
// @User: Advanced
AP_GROUPINFO("GPS_LAG_MS", 2, SIM, gps_delay_ms[0], 100),
// @Param: GPS_TYPE
// @DisplayName: GPS 1 type
@ -472,21 +477,69 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Param: GPS_BYTELOSS
// @DisplayName: GPS Byteloss
// @Description: Percent of bytes lost from GPS 1
// @Units: %
// @User: Advanced
AP_GROUPINFO("GPS_BYTELOSS", 4, SIM, gps_byteloss[0], 0),
// @Param: GPS_NUMSATS
// @DisplayName: GPS 1 Num Satellites
// @Description: Number of satellites GPS 1 has in view
AP_GROUPINFO("GPS_NUMSATS", 5, SIM, gps_numsats[0], 10),
// @Param: GPS_GLITCH
// @DisplayName: GPS 1 Glitch
// @Description: Glitch offsets of simulated GPS 1 sensor
// @Vector3Parameter: 1
// @User: Advanced
AP_GROUPINFO("GPS_GLITCH", 6, SIM, gps_glitch[0], 0),
// @Param: GPS_HZ
// @DisplayName: GPS 1 Hz
// @Description: GPS 1 Update rate
// @Units: Hz
AP_GROUPINFO("GPS_HZ", 7, SIM, gps_hertz[0], 5),
// @Param: GPS_DRIFTALT
// @DisplayName: GPS 1 Altitude Drift
// @Description: GPS 1 altitude drift error
// @Units: m
// @User: Advanced
AP_GROUPINFO("GPS_DRIFTALT", 8, SIM, gps_drift_alt[0], 0),
// @Param: GPS_POS
// @DisplayName: GPS 1 Position
// @Description: GPS 1 antenna phase center position relative to the body frame origin
// @Units: m
// @Vector3Parameter: 1
AP_GROUPINFO("GPS_POS", 9, SIM, gps_pos_offset[0], 0),
// @Param: GPS_NOISE
// @DisplayName: GPS 1 Noise
// @Description: Amplitude of the GPS1 altitude error
// @Units: m
// @User: Advanced
AP_GROUPINFO("GPS_NOISE", 10, SIM, gps_noise[0], 0),
// @Param: GPS_LOCKTIME
// @DisplayName: GPS 1 Lock Time
// @Description: Delay in seconds before GPS1 acquires lock
// @Units: s
// @User: Advanced
AP_GROUPINFO("GPS_LOCKTIME", 11, SIM, gps_lock_time[0], 0),
// @Param: GPS_ALT_OFS
// @DisplayName: GPS 1 Altitude Offset
// @Description: GPS 1 Altitude Error
// @Units: m
AP_GROUPINFO("GPS_ALT_OFS", 12, SIM, gps_alt_offset[0], 0),
// @Param: GPS_HDG
// @DisplayName: GPS 1 Heading
// @Description: Enable GPS1 output of NMEA heading HDT sentence or UBLOX_RELPOSNED
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("GPS_HDG", 13, SIM, gps_hdg_enabled[0], SIM::GPS_HEADING_NONE),
// @Param: GPS_ACC
// @DisplayName: GPS 1 Accuracy
// @Description: GPS 1 Accuracy
// @User: Advanced
AP_GROUPINFO("GPS_ACC", 14, SIM, gps_accuracy[0], 0.3),
// @Param: GPS_VERR
// @DisplayName: GPS 1 Velocity Error
// @Description: GPS 1 Velocity Error Offsets in NED
// @Vector3Parameter: 1
// @User: Advanced
AP_GROUPINFO("GPS_VERR", 15, SIM, gps_vel_err[0], 0),
// @Param: GPS2_DISABLE
// @DisplayName: GPS 2 disable
@ -494,6 +547,11 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Values: 0:Enable, 1:GPS Disabled
// @User: Advanced
AP_GROUPINFO("GPS2_DISABLE", 30, SIM, gps_disable[1], 1),
// @Param: GPS2_LAG_MS
// @DisplayName: GPS 2 Lag
// @Description: GPS 2 lag in ms
// @Units: ms
// @User: Advanced
AP_GROUPINFO("GPS2_LAG_MS", 31, SIM, gps_delay_ms[1], 100),
// @Param: GPS2_TYPE
// @CopyFieldsFrom: SIM_GPS_TYPE
@ -503,27 +561,87 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Param: GPS2_BYTELOS
// @DisplayName: GPS 2 Byteloss
// @Description: Percent of bytes lost from GPS 2
// @Units: %
// @User: Advanced
AP_GROUPINFO("GPS2_BYTELOS", 33, SIM, gps_byteloss[1], 0),
// @Param: GPS2_NUMSATS
// @DisplayName: GPS 2 Num Satellites
// @Description: Number of satellites GPS 2 has in view
AP_GROUPINFO("GPS2_NUMSATS", 34, SIM, gps_numsats[1], 10),
// @Param: GPS2_GLTCH
// @DisplayName: GPS 2 Glitch
// @Description: Glitch offsets of simulated GPS 2 sensor
// @Vector3Parameter: 1
// @User: Advanced
AP_GROUPINFO("GPS2_GLTCH", 35, SIM, gps_glitch[1], 0),
// @Param: GPS2_HZ
// @DisplayName: GPS 2 Hz
// @Description: GPS 2 Update rate
// @Units: Hz
AP_GROUPINFO("GPS2_HZ", 36, SIM, gps_hertz[1], 5),
// @Param: GPS2_DRFTALT
// @DisplayName: GPS 2 Altitude Drift
// @Description: GPS 2 altitude drift error
// @Units: m
// @User: Advanced
AP_GROUPINFO("GPS2_DRFTALT", 37, SIM, gps_drift_alt[1], 0),
// @Param: GPS2_POS
// @DisplayName: GPS 2 Position
// @Description: GPS 2 antenna phase center position relative to the body frame origin
// @Units: m
// @Vector3Parameter: 1
AP_GROUPINFO("GPS2_POS", 38, SIM, gps_pos_offset[1], 0),
// @Param: GPS2_NOISE
// @DisplayName: GPS 2 Noise
// @Description: Amplitude of the GPS2 altitude error
// @Units: m
// @User: Advanced
AP_GROUPINFO("GPS2_NOISE", 39, SIM, gps_noise[1], 0),
// @Param: GPS2_LCKTIME
// @DisplayName: GPS 2 Lock Time
// @Description: Delay in seconds before GPS2 acquires lock
// @Units: s
// @User: Advanced
AP_GROUPINFO("GPS2_LCKTIME", 40, SIM, gps_lock_time[1], 0),
// @Param: GPS2_ALT_OFS
// @DisplayName: GPS 2 Altitude Offset
// @Description: GPS 2 Altitude Error
// @Units: m
AP_GROUPINFO("GPS2_ALT_OFS", 41, SIM, gps_alt_offset[1], 0),
// @Param: GPS2_HDG
// @DisplayName: GPS 2 Heading
// @Description: Enable GPS2 output of NMEA heading HDT sentence or UBLOX_RELPOSNED
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO("GPS2_HDG", 42, SIM, gps_hdg_enabled[1], SIM::GPS_HEADING_NONE),
// @Param: GPS2_ACC
// @DisplayName: GPS 2 Accuracy
// @Description: GPS 2 Accuracy
// @User: Advanced
AP_GROUPINFO("GPS2_ACC", 43, SIM, gps_accuracy[1], 0.3),
// @Param: GPS2_VERR
// @DisplayName: GPS 2 Velocity Error
// @Description: GPS 2 Velocity Error Offsets in NED
// @Vector3Parameter: 1
// @User: Advanced
AP_GROUPINFO("GPS2_VERR", 44, SIM, gps_vel_err[1], 0),
// @Param: INIT_LAT_OFS
// @DisplayName: Initial Latitude Offset
// @Description: GPS initial lat offset from origin
AP_GROUPINFO("INIT_LAT_OFS", 45, SIM, gps_init_lat_ofs, 0),
// @Param: INIT_LON_OFS
// @DisplayName: Initial Longitude Offset
// @Description: GPS initial lon offset from origin
AP_GROUPINFO("INIT_LON_OFS", 46, SIM, gps_init_lon_ofs, 0),
// @Param: INIT_ALT_OFS
// @DisplayName: Initial Altitude Offset
// @Description: GPS initial alt offset from origin
AP_GROUPINFO("INIT_ALT_OFS", 47, SIM, gps_init_alt_ofs, 0),
// @Param: GPS_LOG_NUM
// @DisplayName: GPS Log Number
// @Description: Log number for GPS:update_file()
AP_GROUPINFO("GPS_LOG_NUM", 48, SIM, gps_log_num, 0),
AP_GROUPEND