mirror of https://github.com/ArduPilot/ardupilot
Tools: add ability to simulate more than 2 GPSs
This commit is contained in:
parent
fab1ef7a87
commit
7b64263562
|
@ -552,13 +552,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.start_subtest("Radio failsafe RTL fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 1)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe RTL fails into land mode due to bad position.")
|
||||
|
||||
|
@ -567,13 +567,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.start_subtest("Radio failsafe SmartRTL->RTL fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 4)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe SmartRTL->RTL fails into land mode due to bad position.")
|
||||
|
||||
|
@ -582,13 +582,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to bad position.")
|
||||
self.set_parameter('FS_THR_ENABLE', 5)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.wait_mode("LAND")
|
||||
self.wait_landed_and_disarmed()
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.end_subtest("Completed Radio failsafe SmartRTL->LAND fails into land mode due to bad position.")
|
||||
|
||||
|
@ -597,9 +597,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.start_subtest("Radio failsafe SmartRTL->RTL fails into RTL mode due to no path.")
|
||||
self.set_parameter('FS_THR_ENABLE', 4)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
|
@ -613,9 +613,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.start_subtest("Radio failsafe SmartRTL->LAND fails into land mode due to no path.")
|
||||
self.set_parameter('FS_THR_ENABLE', 5)
|
||||
self.takeoffAndMoveAway()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
|
||||
self.set_parameter('SIM_GPS_DISABLE', 0)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 1)
|
||||
self.wait_ekf_happy()
|
||||
self.delay_sim_time(5)
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
|
@ -1958,8 +1958,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
glitch_current = 0
|
||||
self.progress("Apply first glitch")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# record position for 30 seconds
|
||||
|
@ -1973,15 +1973,15 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
glitch_current = -1
|
||||
self.progress("Completed Glitches")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
else:
|
||||
self.progress("Applying glitch %u" % glitch_current)
|
||||
# move onto the next glitch
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# start displaying distance moved after all glitches applied
|
||||
|
@ -2002,8 +2002,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
# disable gps glitch
|
||||
if glitch_current != -1:
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
if self.use_map:
|
||||
self.show_gps_and_sim_positions(False)
|
||||
|
@ -2024,7 +2024,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.wait_attitude(desroll=0, despitch=0, timeout=10, tolerance=1)
|
||||
|
||||
# apply glitch
|
||||
self.set_parameter("SIM_GPS_GLITCH_X", 0.001)
|
||||
self.set_parameter("SIM_GPS1_GLTCH_X", 0.001)
|
||||
|
||||
# check lean angles remain stable for 20 seconds
|
||||
tstart = self.get_sim_time()
|
||||
|
@ -2098,11 +2098,11 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
# stop and test loss of GPS for a short time - it should resume GPS use without falling back into a non aiding mode
|
||||
self.change_mode("LOITER")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 0,
|
||||
"SIM_GPS1_ENABLE": 1,
|
||||
})
|
||||
# regaining GPS should not result in it falling back to a non-navigation mode
|
||||
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=1)
|
||||
|
@ -2118,8 +2118,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
glitch_current = 0
|
||||
self.progress("Apply first glitch")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# record position for 30 seconds
|
||||
|
@ -2132,15 +2132,15 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
if glitch_current < glitch_num:
|
||||
self.progress("Applying glitch %u" % glitch_current)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS_GLITCH_Y": glitch_lon[glitch_current],
|
||||
"SIM_GPS1_GLTCH_X": glitch_lat[glitch_current],
|
||||
"SIM_GPS1_GLTCH_Y": glitch_lon[glitch_current],
|
||||
})
|
||||
|
||||
# turn off glitching
|
||||
self.progress("Completed Glitches")
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_X": 0,
|
||||
"SIM_GPS_GLITCH_Y": 0,
|
||||
"SIM_GPS1_GLTCH_X": 0,
|
||||
"SIM_GPS1_GLTCH_Y": 0,
|
||||
})
|
||||
|
||||
# continue with the mission
|
||||
|
@ -2526,7 +2526,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.set_parameters({
|
||||
"SIM_FLOW_ENABLE": 1,
|
||||
"FLOW_TYPE": 10,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
"SIM_TERRAIN": 0,
|
||||
})
|
||||
|
||||
|
@ -2980,13 +2980,13 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
'''fly a mission far from the vehicle origin'''
|
||||
# Fly mission #1
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
nz = mavutil.location(-43.730171, 169.983118, 1466.3, 270)
|
||||
self.set_origin(nz)
|
||||
self.set_parameters({
|
||||
"SIM_GPS_DISABLE": 0,
|
||||
"SIM_GPS1_ENABLE": 1,
|
||||
})
|
||||
self.progress("# Load copter_mission")
|
||||
# load the waypoint count
|
||||
|
@ -3028,8 +3028,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"GPS1_TYPE": 9,
|
||||
"GPS2_TYPE": 9,
|
||||
# disable simulated GPS, so only via DroneCAN
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS2_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 0,
|
||||
# this ensures we use DroneCAN baro and compass
|
||||
"SIM_BARO_COUNT" : 0,
|
||||
"SIM_MAG1_DEVID" : 0,
|
||||
|
@ -3206,7 +3206,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"EK3_SRC1_POSZ": 3,
|
||||
"EK3_AFFINITY" : 1,
|
||||
"GPS2_TYPE" : 1,
|
||||
"SIM_GPS2_DISABLE" : 0,
|
||||
"SIM_GPS2_ENABLE" : 1,
|
||||
"SIM_GPS2_GLTCH_Z" : -30
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
@ -7245,7 +7245,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.context_push()
|
||||
self.set_parameters({
|
||||
"GPS1_TYPE": 2,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
# if there is no GPS at all then we must direct EK3 to not use
|
||||
# it at all. Otherwise it will never initialise, as it wants
|
||||
|
@ -8986,7 +8986,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"RNGFND1_POS_Y": -0.07,
|
||||
"RNGFND1_POS_Z": -0.005,
|
||||
"SIM_SONAR_SCALE": 30,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
|
@ -9045,7 +9045,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.set_parameters({
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
@ -9116,9 +9116,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
|
@ -9176,9 +9176,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
|
@ -9186,8 +9186,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
# configure velocity errors such that the 1st GPS should be
|
||||
# 4/5, second GPS 1/5 of result (0.5**2)/((0.5**2)+(1.0**2))
|
||||
self.set_parameters({
|
||||
"SIM_GPS_VERR_X": 0.3, # m/s
|
||||
"SIM_GPS_VERR_Y": 0.4,
|
||||
"SIM_GPS1_VERR_X": 0.3, # m/s
|
||||
"SIM_GPS1_VERR_Y": 0.4,
|
||||
"SIM_GPS2_VERR_X": 0.6, # m/s
|
||||
"SIM_GPS2_VERR_Y": 0.8,
|
||||
"GPS_BLEND_MASK": 4, # use only speed for blend calculations
|
||||
|
@ -9243,9 +9243,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"WP_YAW_BEHAVIOR": 0, # do not yaw
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS_POS_X": 1.0,
|
||||
"SIM_GPS_POS_Y": -1.0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_GPS1_POS_X": 1.0,
|
||||
"SIM_GPS1_POS_Y": -1.0,
|
||||
"SIM_GPS2_POS_X": -1.0,
|
||||
"SIM_GPS2_POS_Y": 1.0,
|
||||
"GPS_AUTO_SWITCH": 2,
|
||||
|
@ -11739,7 +11739,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
'''ensure Guided acts appropriately when force-armed'''
|
||||
self.set_parameters({
|
||||
"EK3_SRC2_VELXY": 5,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.load_default_params_file("copter-optflow.parm")
|
||||
self.reboot_sitl()
|
||||
|
@ -11926,7 +11926,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
'''check FlightOption::REQUIRE_POSITION_FOR_ARMING works'''
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
"SIM_GPS_NUMSATS": 3, # EKF does not like < 6
|
||||
"SIM_GPS1_NUMSATS": 3, # EKF does not like < 6
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.change_mode('STABILIZE')
|
||||
|
@ -12127,7 +12127,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
|
||||
# switch to EKF3
|
||||
self.set_parameters({
|
||||
'SIM_GPS_GLITCH_X' : 0.001, # about 100m
|
||||
'SIM_GPS1_GLTCH_X' : 0.001, # about 100m
|
||||
'EK3_CHECK_SCALE' : 100,
|
||||
'AHRS_EKF_TYPE' : 3})
|
||||
|
||||
|
|
|
@ -185,7 +185,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
def NeedEKFToArm(self):
|
||||
"""Ensure the EKF must be healthy for the vehicle to arm."""
|
||||
self.progress("Ensuring we need EKF to be healthy to arm")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.context_collect("STATUSTEXT")
|
||||
tstart = self.get_sim_time()
|
||||
success = False
|
||||
|
@ -201,7 +201,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
except AutoTestTimeoutException:
|
||||
pass
|
||||
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
def fly_LOITER(self, num_circles=4):
|
||||
|
@ -2046,14 +2046,14 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.delay_sim_time(60)
|
||||
else:
|
||||
self.delay_sim_time(20)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.progress("Continue orbit without GPS")
|
||||
self.delay_sim_time(20)
|
||||
self.change_mode("RTL")
|
||||
self.wait_distance_to_home(100, 200, timeout=200)
|
||||
# go into LOITER to create additonal time for a GPS re-enable test
|
||||
self.change_mode("LOITER")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
t_enabled = self.get_sim_time()
|
||||
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
|
||||
# to prevent bad GPS being used when coming back after loss of lock due to interence.
|
||||
|
@ -2064,9 +2064,9 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.delay_sim_time(20)
|
||||
|
||||
self.set_parameter("AHRS_OPTIONS", 1)
|
||||
self.set_parameter("SIM_GPS_JAM", 1)
|
||||
self.set_parameter("SIM_GPS1_JAM", 1)
|
||||
self.delay_sim_time(10)
|
||||
self.set_parameter("SIM_GPS_JAM", 0)
|
||||
self.set_parameter("SIM_GPS1_JAM", 0)
|
||||
t_enabled = self.get_sim_time()
|
||||
# The EKF should wait for GPS checks to pass when we are still able to navigate using dead reckoning
|
||||
# to prevent bad GPS being used when coming back after loss of lock due to interence.
|
||||
|
@ -3325,7 +3325,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
"EK3_AFFINITY": 15, # enable affinity for all sensors
|
||||
"EK3_IMU_MASK": 3, # use only 2 IMUs
|
||||
"GPS2_TYPE": 1,
|
||||
"SIM_GPS2_DISABLE": 0,
|
||||
"SIM_GPS2_ENABLE": 1,
|
||||
"SIM_BARO_COUNT": 2,
|
||||
"SIM_BAR2_DISABLE": 0,
|
||||
"ARSPD2_TYPE": 2,
|
||||
|
@ -3400,9 +3400,9 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
# noise on each axis
|
||||
def sim_gps_verr():
|
||||
self.set_parameters({
|
||||
"SIM_GPS_VERR_X": self.get_parameter("SIM_GPS_VERR_X") + 2,
|
||||
"SIM_GPS_VERR_Y": self.get_parameter("SIM_GPS_VERR_Y") + 2,
|
||||
"SIM_GPS_VERR_Z": self.get_parameter("SIM_GPS_VERR_Z") + 2,
|
||||
"SIM_GPS1_VERR_X": self.get_parameter("SIM_GPS1_VERR_X") + 2,
|
||||
"SIM_GPS1_VERR_Y": self.get_parameter("SIM_GPS1_VERR_Y") + 2,
|
||||
"SIM_GPS1_VERR_Z": self.get_parameter("SIM_GPS1_VERR_Z") + 2,
|
||||
})
|
||||
self.wait_statustext(text="EKF3 lane switch", timeout=30, the_function=sim_gps_verr, check_context=True)
|
||||
if self.lane_switches != [1, 0, 1]:
|
||||
|
@ -4870,8 +4870,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.context_collect('STATUSTEXT')
|
||||
self.set_parameters({
|
||||
"EK3_POS_I_GATE": 0,
|
||||
"SIM_GPS_HZ": 1,
|
||||
"SIM_GPS_LAG_MS": 1000,
|
||||
"SIM_GPS1_HZ": 1,
|
||||
"SIM_GPS1_LAG_MS": 1000,
|
||||
})
|
||||
self.wait_statustext("DCM Active", check_context=True, timeout=60)
|
||||
self.wait_statustext("EKF3 Active", check_context=True)
|
||||
|
@ -5530,8 +5530,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
def AltResetBadGPS(self):
|
||||
'''Tests the handling of poor GPS lock pre-arm alt resets'''
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_Z": 0,
|
||||
"SIM_GPS_ACC": 0.3,
|
||||
"SIM_GPS1_GLTCH_Z": 0,
|
||||
"SIM_GPS1_ACC": 0.3,
|
||||
})
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
|
@ -5541,8 +5541,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
raise NotAchievedException("Bad relative alt %.1f" % relalt)
|
||||
|
||||
self.progress("Setting low accuracy, glitching GPS")
|
||||
self.set_parameter("SIM_GPS_ACC", 40)
|
||||
self.set_parameter("SIM_GPS_GLITCH_Z", -47)
|
||||
self.set_parameter("SIM_GPS1_ACC", 40)
|
||||
self.set_parameter("SIM_GPS1_GLTCH_Z", -47)
|
||||
|
||||
self.progress("Waiting 10s for height update")
|
||||
self.delay_sim_time(10)
|
||||
|
@ -6119,7 +6119,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.takeoff(50)
|
||||
self.change_mode('GUIDED')
|
||||
self.context_push()
|
||||
self.set_parameter('SIM_GPS_DISABLE', 1)
|
||||
self.set_parameter('SIM_GPS1_ENABLE', 0)
|
||||
self.delay_sim_time(30)
|
||||
self.set_attitude_target()
|
||||
self.context_pop()
|
||||
|
@ -6196,7 +6196,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
|
||||
def ForceArm(self):
|
||||
'''check force-arming functionality'''
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
# 21196 is the mavlink standard, 2989 is legacy
|
||||
for magic_value in 21196, 2989:
|
||||
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK,
|
||||
|
|
|
@ -18,7 +18,7 @@ WPNAV_SPEED_DN 300
|
|||
WPNAV_SPEED 2000
|
||||
RTL_ALT 2500
|
||||
ANGLE_MAX 3000
|
||||
SIM_GPS_LAG_MS 0
|
||||
SIM_GPS1_LAG_MS 0
|
||||
GPS_DELAY_MS 20
|
||||
INS_GYRO_FILTER 50
|
||||
INS_ACCEL_FILTER 50
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
# SITL GPS-for-yaw using a single simulated NMEA GPS
|
||||
EK3_SRC1_YAW 2
|
||||
GPS1_TYPE 5
|
||||
SIM_GPS_TYPE 5
|
||||
SIM_GPS_HDG 1
|
||||
SIM_GPS1_TYPE 5
|
||||
SIM_GPS1_HDG 1
|
||||
|
|
|
@ -5,7 +5,8 @@ GPS1_TYPE 17
|
|||
GPS2_TYPE 18
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS1_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
SIM_GPS2_ENABLE 1
|
||||
SIM_GPS2_HDG 1
|
||||
SIM_GPS1_HDG 4
|
||||
|
|
|
@ -5,7 +5,8 @@ GPS1_TYPE 17
|
|||
GPS2_TYPE 18
|
||||
GPS1_POS_Y -0.2
|
||||
GPS2_POS_Y 0.2
|
||||
SIM_GPS_POS_Y -0.2
|
||||
SIM_GPS1_POS_Y -0.2
|
||||
SIM_GPS2_POS_Y 0.2
|
||||
SIM_GPS2_DISABLE 0
|
||||
SIM_GPS2_ENABLE 1
|
||||
SIM_GPS2_HDG 1
|
||||
SIM_GPS1_HDG 4
|
||||
|
|
|
@ -628,19 +628,12 @@ SIM_FLOW_POS_X,0
|
|||
SIM_FLOW_POS_Y,0
|
||||
SIM_FLOW_POS_Z,0
|
||||
SIM_FLOW_RATE,10
|
||||
SIM_GP2_GLITCH_X,0
|
||||
SIM_GP2_GLITCH_Y,0
|
||||
SIM_GP2_GLITCH_Z,0
|
||||
SIM_GPS_BYTELOSS,0
|
||||
SIM_GPS_DISABLE,0
|
||||
SIM_GPS_DRIFTALT,0
|
||||
SIM_GPS_GLITCH_X,0
|
||||
SIM_GPS_GLITCH_Y,0
|
||||
SIM_GPS_GLITCH_Z,0
|
||||
SIM_GPS_HZ,5
|
||||
SIM_GPS_NOISE,0
|
||||
SIM_GPS_NUMSATS,10
|
||||
SIM_GPS_TYPE,1
|
||||
SIM_GPS1_BYTELOSS,0
|
||||
SIM_GPS1_DRIFTALT,0
|
||||
SIM_GPS1_HZ,5
|
||||
SIM_GPS1_NOISE,0
|
||||
SIM_GPS1_NUMSATS,10
|
||||
SIM_GPS1_TYPE,1
|
||||
SIM_GPS2_ENABLE,0
|
||||
SIM_IMU_POS_X,0
|
||||
SIM_IMU_POS_Y,0
|
||||
|
|
|
@ -1764,8 +1764,8 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
|||
|
||||
# Kill any GPSs
|
||||
self.set_parameters({
|
||||
'SIM_GPS_DISABLE': 1,
|
||||
'SIM_GPS2_DISABLE': 1,
|
||||
'SIM_GPS1_ENABLE': 0,
|
||||
'SIM_GPS2_ENABLE': 0,
|
||||
})
|
||||
self.delay_sim_time(5)
|
||||
|
||||
|
|
|
@ -6807,7 +6807,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
'''Test jamming simulation works'''
|
||||
self.wait_ready_to_arm()
|
||||
start_loc = self.assert_receive_message('GPS_RAW_INT')
|
||||
self.set_parameter("SIM_GPS_JAM", 1)
|
||||
self.set_parameter("SIM_GPS1_JAM", 1)
|
||||
|
||||
class Requirement():
|
||||
def __init__(self, field, min_value):
|
||||
|
|
|
@ -3665,7 +3665,7 @@ class TestSuite(ABC):
|
|||
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:
|
||||
raise NotAchievedException("Expected GPS to be OK")
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)
|
||||
self.set_parameter("SIM_GPS_TYPE", 0)
|
||||
self.set_parameter("SIM_GPS1_TYPE", 0)
|
||||
self.delay_sim_time(10)
|
||||
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
|
@ -3674,7 +3674,7 @@ class TestSuite(ABC):
|
|||
raise NotAchievedException("Expected GPS to be failed")
|
||||
|
||||
self.start_subtest("HIGH_LATENCY2 location")
|
||||
self.set_parameter("SIM_GPS_TYPE", 1)
|
||||
self.set_parameter("SIM_GPS1_TYPE", 1)
|
||||
self.delay_sim_time(10)
|
||||
m = self.poll_message("HIGH_LATENCY2")
|
||||
self.progress(self.dump_message_verbose(m))
|
||||
|
@ -8471,7 +8471,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
|
||||
def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):
|
||||
"""Disable GPS and wait for EKF to report the end of assistance from GPS."""
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
tstart = self.get_sim_time()
|
||||
|
||||
""" if using SITL estimates directly """
|
||||
|
@ -10683,7 +10683,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
p1=1, # ARM
|
||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
|
||||
)
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.wait_ekf_happy() # EKF may stay unhappy for a while
|
||||
self.progress("PASS not able to arm without Position in mode : %s" % mode)
|
||||
if mode in self.get_no_position_not_settable_modes_list():
|
||||
|
@ -10693,10 +10693,10 @@ Also, ignores heartbeats not from our target system'''
|
|||
try:
|
||||
self.change_mode(mode, timeout=15)
|
||||
except AutoTestTimeoutException:
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.progress("PASS not able to set mode without Position : %s" % mode)
|
||||
except ValueError:
|
||||
self.set_parameter("SIM_GPS_DISABLE", 0)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 1)
|
||||
self.progress("PASS not able to set mode without Position : %s" % mode)
|
||||
if mode == "FOLLOW":
|
||||
self.set_parameter("FOLL_ENABLE", 0)
|
||||
|
@ -12531,7 +12531,7 @@ switch value'''
|
|||
self.context_collect("STATUSTEXT")
|
||||
self.set_parameters({
|
||||
"AFS_MAX_GPS_LOSS": 1,
|
||||
"SIM_GPS_DISABLE": 1,
|
||||
"SIM_GPS1_ENABLE": 0,
|
||||
})
|
||||
self.wait_statustext("AFS State: GPS_LOSS", check_context=True)
|
||||
self.context_pop()
|
||||
|
@ -14160,7 +14160,7 @@ switch value'''
|
|||
self.context_collect("STATUSTEXT")
|
||||
for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:
|
||||
self.start_subtest("Checking GPS type %s" % name)
|
||||
self.set_parameter("SIM_GPS_TYPE", sim_gps_type)
|
||||
self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)
|
||||
self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)
|
||||
if gps_type is None:
|
||||
gps_type = 1 # auto-detect
|
||||
|
@ -14265,7 +14265,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)
|
||||
self.set_parameter("SIM_GPS2_ENABLE", 1)
|
||||
# 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
|
||||
|
@ -14281,9 +14281,9 @@ switch value'''
|
|||
raise NotAchievedException("Incorrect fix type")
|
||||
|
||||
self.start_subtest("Check parameters are per-GPS")
|
||||
self.assert_parameter_value("SIM_GPS_NUMSATS", 10)
|
||||
self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)
|
||||
self.assert_gps_satellite_count("GPS_RAW_INT", 10)
|
||||
self.set_parameter("SIM_GPS_NUMSATS", 13)
|
||||
self.set_parameter("SIM_GPS1_NUMSATS", 13)
|
||||
self.assert_gps_satellite_count("GPS_RAW_INT", 13)
|
||||
|
||||
self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)
|
||||
|
@ -14311,7 +14311,7 @@ switch value'''
|
|||
if abs(gpi_alt - new_gpi_alt) > 100:
|
||||
raise NotAchievedException("alt moved unexpectedly")
|
||||
self.progress("Killing first GPS")
|
||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||
self.set_parameter("SIM_GPS1_ENABLE", 0)
|
||||
self.delay_sim_time(1)
|
||||
self.progress("Checking altitude now matches second GPS")
|
||||
m = self.assert_receive_message("GLOBAL_POSITION_INT")
|
||||
|
|
|
@ -17,7 +17,6 @@ module load graph
|
|||
@alias add odroidpower relay set 0
|
||||
@alias add neutral2 servo set 12 1500
|
||||
@alias add ekf param set AHRS_EKF_USE
|
||||
@alias add gpsdisable param set SIM_GPS_DISABLE
|
||||
@alias add bb status gps* scaled* raw*
|
||||
@alias add g graph
|
||||
@alias add grc3 g RC_CHANNELS.chan3_raw SERVO_OUTPUT_RAW.servo3_raw
|
||||
|
|
Loading…
Reference in New Issue