mirror of https://github.com/ArduPilot/ardupilot
Tools: re-work copter and plane loss of GPS auto tests
Explicitly test time taken to reset to GPS loss and regain of lock for copter without and plane with dead reckoning assistance.
This commit is contained in:
parent
2c3174b77b
commit
2b027a7265
|
@ -1922,6 +1922,22 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
self.show_gps_and_sim_positions(False)
|
self.show_gps_and_sim_positions(False)
|
||||||
raise e
|
raise e
|
||||||
|
|
||||||
|
# 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,
|
||||||
|
})
|
||||||
|
self.delay_sim_time(2)
|
||||||
|
self.set_parameters({
|
||||||
|
"SIM_GPS_DISABLE": 0,
|
||||||
|
})
|
||||||
|
# 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)
|
||||||
|
# It should still be navigating after enougnh time has passed for any pending timeouts to activate.
|
||||||
|
self.delay_sim_time(10)
|
||||||
|
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=1)
|
||||||
|
self.change_mode("AUTO")
|
||||||
|
|
||||||
# record time and position
|
# record time and position
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
|
|
||||||
|
|
|
@ -2195,8 +2195,28 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||||
self.delay_sim_time(20)
|
self.delay_sim_time(20)
|
||||||
self.change_mode("RTL")
|
self.change_mode("RTL")
|
||||||
self.wait_distance_to_home(100, 200, timeout=200)
|
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_GPS_DISABLE", 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.
|
||||||
|
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=15)
|
||||||
|
if self.get_sim_time() < (t_enabled+9):
|
||||||
|
raise NotAchievedException("GPS use re-started too quickly")
|
||||||
|
# wait for EKF and vehicle position to stabilise, then test response to jamming
|
||||||
|
self.delay_sim_time(20)
|
||||||
|
|
||||||
|
self.set_parameter("AHRS_OPTIONS", 1)
|
||||||
|
self.set_parameter("SIM_GPS_JAM", 1)
|
||||||
self.delay_sim_time(10)
|
self.delay_sim_time(10)
|
||||||
|
self.set_parameter("SIM_GPS_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.
|
||||||
|
self.wait_ekf_flags(mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS, 0, timeout=15)
|
||||||
|
if self.get_sim_time() < (t_enabled+9):
|
||||||
|
raise NotAchievedException("GPS use re-started too quickly after jamming")
|
||||||
self.set_rc(3, 1000)
|
self.set_rc(3, 1000)
|
||||||
self.fly_home_land_and_disarm()
|
self.fly_home_land_and_disarm()
|
||||||
self.progress("max-divergence: %fm" % (self.max_divergence,))
|
self.progress("max-divergence: %fm" % (self.max_divergence,))
|
||||||
|
|
Loading…
Reference in New Issue