mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed GPS POS parameters
SIM_GPS2_POS1_* makes no sense
This commit is contained in:
parent
05194ed8b6
commit
bce4fd43a3
|
@ -278,7 +278,7 @@ const AP_Param::GroupInfo SITL::var_gps[] = {
|
||||||
AP_GROUPINFO("GPS_GLITCH", 6, SITL, gps_glitch[0], 0),
|
AP_GROUPINFO("GPS_GLITCH", 6, SITL, gps_glitch[0], 0),
|
||||||
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz[0], 5),
|
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz[0], 5),
|
||||||
AP_GROUPINFO("GPS_DRIFTALT", 8, SITL, gps_drift_alt[0], 0),
|
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_POS", 9, SITL, gps_pos_offset[0], 0),
|
||||||
AP_GROUPINFO("GPS_NOISE", 10, SITL, gps_noise[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_LOCKTIME", 11, SITL, gps_lock_time[0], 0),
|
||||||
AP_GROUPINFO("GPS_ALT_OFS", 12, SITL, gps_alt_offset[0], 0),
|
AP_GROUPINFO("GPS_ALT_OFS", 12, SITL, gps_alt_offset[0], 0),
|
||||||
|
@ -294,7 +294,7 @@ const AP_Param::GroupInfo SITL::var_gps[] = {
|
||||||
AP_GROUPINFO("GPS2_GLTCH", 35, SITL, gps_glitch[1], 0),
|
AP_GROUPINFO("GPS2_GLTCH", 35, SITL, gps_glitch[1], 0),
|
||||||
AP_GROUPINFO("GPS2_HZ", 36, SITL, gps_hertz[1], 5),
|
AP_GROUPINFO("GPS2_HZ", 36, SITL, gps_hertz[1], 5),
|
||||||
AP_GROUPINFO("GPS2_DRFTALT", 37, SITL, gps_drift_alt[1], 0),
|
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_POS", 38, SITL, gps_pos_offset[1], 0),
|
||||||
AP_GROUPINFO("GPS2_NOISE", 39, SITL, gps_noise[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_LCKTIME", 40, SITL, gps_lock_time[1], 0),
|
||||||
AP_GROUPINFO("GPS2_ALT_OFS", 41, SITL, gps_alt_offset[1], 0),
|
AP_GROUPINFO("GPS2_ALT_OFS", 41, SITL, gps_alt_offset[1], 0),
|
||||||
|
|
Loading…
Reference in New Issue