|
|
|
@ -238,24 +238,34 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
@@ -238,24 +238,34 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
|
|
|
|
|
|
|
|
|
|
// GPS SITL parameters
|
|
|
|
|
const AP_Param::GroupInfo SITL::var_gps[] = { |
|
|
|
|
AP_GROUPINFO("GPS_DISABLE", 1, SITL, gps_disable, 0), |
|
|
|
|
AP_GROUPINFO("GPS_DELAY", 2, SITL, gps_delay, 1), |
|
|
|
|
AP_GROUPINFO("GPS_DISABLE", 1, SITL, gps_disable[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_DELAY", 2, SITL, gps_delay[0], 1), |
|
|
|
|
AP_GROUPINFO("GPS_TYPE", 3, SITL, gps_type[0], SITL::GPS_TYPE_UBLOX), |
|
|
|
|
AP_GROUPINFO("GPS_BYTELOSS", 4, SITL, gps_byteloss, 0), |
|
|
|
|
AP_GROUPINFO("GPS_NUMSATS", 5, SITL, gps_numsats, 10), |
|
|
|
|
AP_GROUPINFO("GPS_BYTELOSS", 4, SITL, gps_byteloss[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_NUMSATS", 5, SITL, gps_numsats[0], 10), |
|
|
|
|
AP_GROUPINFO("GPS_GLITCH", 6, SITL, gps_glitch[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz, 5), |
|
|
|
|
AP_GROUPINFO("GPS2_ENABLE", 8, SITL, gps2_enable, 0), |
|
|
|
|
AP_GROUPINFO("GPS_DRIFTALT", 9, SITL, gps_drift_alt, 0), |
|
|
|
|
AP_GROUPINFO("GPS_POS1", 10, SITL, gps_pos_offset[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_NOISE", 11, SITL, gps_noise, 0), |
|
|
|
|
AP_GROUPINFO("GP2_GLITCH", 12, SITL, gps_glitch[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_TYPE", 13, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX), |
|
|
|
|
AP_GROUPINFO("GPS_LOCKTIME", 14, SITL, gps_lock_time, 0), |
|
|
|
|
AP_GROUPINFO("GPS_ALT_OFS", 15, SITL, gps_alt_offset, 0), |
|
|
|
|
AP_GROUPINFO("GPS_HDG", 16, SITL, gps_hdg_enabled[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_POS2", 17, SITL, gps_pos_offset[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_HDG", 18, SITL, gps_hdg_enabled[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz[0], 5), |
|
|
|
|
AP_GROUPINFO("GPS_DRIFTALT", 8, SITL, gps_drift_alt[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_POS1", 9, SITL, gps_pos_offset[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_NOISE", 10, SITL, gps_noise[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_LOCKTIME", 11, SITL, gps_lock_time[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_ALT_OFS", 12, SITL, gps_alt_offset[0], 0), |
|
|
|
|
AP_GROUPINFO("GPS_HDG", 13, SITL, gps_hdg_enabled[0], 0), |
|
|
|
|
|
|
|
|
|
AP_GROUPINFO("GPS2_DISABLE", 30, SITL, gps_disable[1], 1), |
|
|
|
|
AP_GROUPINFO("GPS2_DELAY", 31, SITL, gps_delay[1], 1), |
|
|
|
|
AP_GROUPINFO("GPS2_TYPE", 32, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX), |
|
|
|
|
AP_GROUPINFO("GPS2_BYTELOS", 33, SITL, gps_byteloss[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_NUMSATS", 34, SITL, gps_numsats[1], 10), |
|
|
|
|
AP_GROUPINFO("GPS2_GLTCH", 35, SITL, gps_glitch[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_HZ", 36, SITL, gps_hertz[1], 5), |
|
|
|
|
AP_GROUPINFO("GPS2_DRFTALT", 37, SITL, gps_drift_alt[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_POS1", 38, SITL, gps_pos_offset[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_NOISE", 39, SITL, gps_noise[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_LCKTIME", 40, SITL, gps_lock_time[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_ALT_OFS", 41, SITL, gps_alt_offset[1], 0), |
|
|
|
|
AP_GROUPINFO("GPS2_HDG", 42, SITL, gps_hdg_enabled[1], 0), |
|
|
|
|
|
|
|
|
|
AP_GROUPEND |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|