mirror of https://github.com/ArduPilot/ardupilot
Tools: adjust for GPS parameter renames
This commit is contained in:
parent
fe21c576c8
commit
89bdb14916
|
@ -2681,7 +2681,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.set_parameters({
|
||||
"CAN_P1_DRIVER": 1,
|
||||
"GPS_TYPE": 9,
|
||||
"GPS_TYPE2": 9,
|
||||
"GPS2_TYPE": 9,
|
||||
# disable simulated GPS, so only via DroneCAN
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS2_DISABLE": 1,
|
||||
|
@ -2729,7 +2729,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
for case in GPS_Order_Tests:
|
||||
self.progress("############################### Trying Case: " + str(case))
|
||||
self.set_parameters({
|
||||
"GPS1_CAN_OVRIDE": case[0],
|
||||
"GPS_CAN_OVRIDE": case[0],
|
||||
"GPS2_CAN_OVRIDE": case[1],
|
||||
})
|
||||
self.drain_mav()
|
||||
|
@ -2860,7 +2860,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.set_parameters({
|
||||
"EK3_SRC1_POSZ": 3,
|
||||
"EK3_AFFINITY" : 1,
|
||||
"GPS_TYPE2" : 1,
|
||||
"GPS2_TYPE" : 1,
|
||||
"SIM_GPS2_DISABLE" : 0,
|
||||
"SIM_GPS2_GLTCH_Z" : -30
|
||||
})
|
||||
|
@ -8640,13 +8640,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"EK2_ENABLE": 1,
|
||||
"AHRS_TRIM_X": 0.01,
|
||||
"AHRS_TRIM_Y": -0.03,
|
||||
"GPS_TYPE2": 1,
|
||||
"GPS_POS1_X": 0.1,
|
||||
"GPS_POS1_Y": 0.2,
|
||||
"GPS_POS1_Z": 0.3,
|
||||
"GPS_POS2_X": -0.1,
|
||||
"GPS_POS2_Y": -0.02,
|
||||
"GPS_POS2_Z": -0.31,
|
||||
"GPS2_TYPE": 1,
|
||||
"GPS_POS_X": 0.1,
|
||||
"GPS_POS_Y": 0.2,
|
||||
"GPS_POS_Z": 0.3,
|
||||
"GPS2_POS_X": -0.1,
|
||||
"GPS2_POS_Y": -0.02,
|
||||
"GPS2_POS_Z": -0.31,
|
||||
"INS_POS1_X": 0.12,
|
||||
"INS_POS1_Y": 0.14,
|
||||
"INS_POS1_Z": -0.02,
|
||||
|
@ -8717,7 +8717,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
try:
|
||||
# configure:
|
||||
self.set_parameters({
|
||||
"GPS_TYPE2": 1,
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
|
|
|
@ -3486,7 +3486,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
"AHRS_EKF_TYPE": 3,
|
||||
"EK3_AFFINITY": 15, # enable affinity for all sensors
|
||||
"EK3_IMU_MASK": 3, # use only 2 IMUs
|
||||
"GPS_TYPE2": 1,
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_BARO_COUNT": 2,
|
||||
"SIM_BAR2_DISABLE": 0,
|
||||
|
|
|
@ -2,9 +2,9 @@
|
|||
EK3_SRC1_YAW 2
|
||||
GPS_AUTO_CONFIG 0
|
||||
GPS_TYPE 17
|
||||
GPS_TYPE2 18
|
||||
GPS_POS1_Y -0.2
|
||||
GPS_POS2_Y 0.2
|
||||
GPS2_TYPE 18
|
||||
GPS_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
|
|
|
@ -2,9 +2,9 @@
|
|||
EK3_SRC1_YAW 2
|
||||
GPS_AUTO_CONFIG 0
|
||||
GPS_TYPE 17
|
||||
GPS_TYPE2 18
|
||||
GPS_POS1_Y -0.2
|
||||
GPS_POS2_Y 0.2
|
||||
GPS2_TYPE 18
|
||||
GPS_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
|
|
|
@ -225,24 +225,24 @@ GPS_BLEND_TC,10
|
|||
GPS_DELAY_MS,0
|
||||
GPS_DELAY_MS2,0
|
||||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS2_GNSS_MODE,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0
|
||||
GPS_POS1_Y,0
|
||||
GPS_POS1_Z,0
|
||||
GPS_POS2_X,0
|
||||
GPS_POS2_Y,0
|
||||
GPS_POS2_Z,0
|
||||
GPS_POS_X,0
|
||||
GPS_POS_Y,0
|
||||
GPS_POS_Z,0
|
||||
GPS2_POS_X,0
|
||||
GPS2_POS_Y,0
|
||||
GPS2_POS_Z,0
|
||||
GPS_RATE_MS,200
|
||||
GPS_RATE_MS2,200
|
||||
GPS2_RATE_MS,200
|
||||
GPS_RAW_DATA,0
|
||||
GPS_SAVE_CFG,0
|
||||
GPS_SBAS_MODE,2
|
||||
GPS_SBP_LOGMASK,-32768
|
||||
GPS_TYPE,1
|
||||
GPS_TYPE2,0
|
||||
GPS2_TYPE,0
|
||||
GROUND_STEER_ALT,0
|
||||
GROUND_STEER_DPS,90
|
||||
ICE_ENABLE,0
|
||||
|
|
|
@ -12062,7 +12062,7 @@ switch value'''
|
|||
def NMEAOutput(self):
|
||||
'''Test AHRS NMEA Output can be read by out NMEA GPS'''
|
||||
self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output
|
||||
self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA
|
||||
self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA
|
||||
port = self.spare_network_port()
|
||||
self.customise_SITL_commandline([
|
||||
"--serial4=tcp:%u" % port, # GPS2 is NMEA....
|
||||
|
@ -13656,10 +13656,10 @@ switch value'''
|
|||
'''check ArduPilot behaviour across multiple GPS units'''
|
||||
self.assert_message_rate_hz('GPS2_RAW', 0)
|
||||
|
||||
# we start sending GPS_TYPE2 - but it will never actually be
|
||||
# we start sending GPS2_TYPE - but it will never actually be
|
||||
# filled in as _port[1] is only filled in in AP_GPS::init()
|
||||
self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")
|
||||
self.set_parameter("GPS_TYPE2", 1)
|
||||
self.set_parameter("GPS2_TYPE", 1)
|
||||
self.assert_message_rate_hz('GPS2_RAW', 5)
|
||||
|
||||
self.start_subtest("Ensure correct fix type when no connected GPS")
|
||||
|
@ -13671,7 +13671,7 @@ switch value'''
|
|||
self.start_subtest("Ensure detection when sim gps connected")
|
||||
self.set_parameter("SIM_GPS2_TYPE", 1)
|
||||
self.set_parameter("SIM_GPS2_DISABLE", 0)
|
||||
# a reboot is required after setting GPS_TYPE2. We start
|
||||
# a reboot is required after setting GPS2_TYPE. We start
|
||||
# sending GPS2_RAW out, once the parameter is set, but a
|
||||
# reboot is required because _port[1] is only set in
|
||||
# AP_GPS::init() at boot time, so it will never be detected.
|
||||
|
|
|
@ -172,9 +172,9 @@ GPS_AUTO_SWITCH,1
|
|||
GPS_BLEND_MASK,5
|
||||
GPS_BLEND_TC,10
|
||||
GPS_DELAY_MS,0
|
||||
GPS_DELAY_MS2,0
|
||||
GPS2_DELAY_MS,0
|
||||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS2_GNSS_MODE,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
|
@ -185,7 +185,7 @@ GPS2_POS_X,0
|
|||
GPS2_POS_Y,0
|
||||
GPS2_POS_Z,0
|
||||
GPS_RATE_MS,200
|
||||
GPS_RATE_MS2,200
|
||||
GPS2_RATE_MS,200
|
||||
GPS_RAW_DATA,0
|
||||
GPS_SAVE_CFG,0
|
||||
GPS_SBAS_MODE,2
|
||||
|
|
|
@ -176,9 +176,9 @@ GPS_AUTO_SWITCH,1
|
|||
GPS_BLEND_MASK,5
|
||||
GPS_BLEND_TC,10
|
||||
GPS_DELAY_MS,0
|
||||
GPS_DELAY_MS2,0
|
||||
GPS2_DELAY_MS,0
|
||||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS2_GNSS_MODE,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
|
@ -189,7 +189,7 @@ GPS2_POS_X,0
|
|||
GPS2_POS_Y,0
|
||||
GPS2_POS_Z,0
|
||||
GPS_RATE_MS,200
|
||||
GPS_RATE_MS2,200
|
||||
GPS2_RATE_MS,200
|
||||
GPS_RAW_DATA,0
|
||||
GPS_SAVE_CFG,0
|
||||
GPS_SBAS_MODE,2
|
||||
|
|
Loading…
Reference in New Issue