Tools: Allow dead reckoning test longer to learn wind if no aspd sensor
This commit is contained in:
parent
87bf8d9997
commit
8639543cdd
@ -2188,10 +2188,14 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
|
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
|
||||||
)
|
)
|
||||||
self.wait_location(loc, accuracy=100)
|
self.wait_location(loc, accuracy=100)
|
||||||
self.progress("Stewing")
|
self.progress("Orbit with GPS and learn wind")
|
||||||
self.delay_sim_time(20)
|
# allow longer to learn wind if there is no airspeed sensor
|
||||||
|
if disable_airspeed_sensor:
|
||||||
|
self.delay_sim_time(60)
|
||||||
|
else:
|
||||||
|
self.delay_sim_time(20)
|
||||||
self.set_parameter("SIM_GPS_DISABLE", 1)
|
self.set_parameter("SIM_GPS_DISABLE", 1)
|
||||||
self.progress("Roasting")
|
self.progress("Continue orbit without GPS")
|
||||||
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)
|
||||||
|
Loading…
Reference in New Issue
Block a user