mirror of https://github.com/ArduPilot/ardupilot
autotest: update SIM_ENGINE_FAIL to mask
This commit is contained in:
parent
dee88b4ecb
commit
726e05afb2
|
@ -1374,7 +1374,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
|
||||
# cut motor 1's to efficiency
|
||||
self.progress("Cutting motor 1 to 65% efficiency")
|
||||
self.set_parameter("SIM_ENGINE_MUL", 0.65)
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_MUL": 0.65,
|
||||
"SIM_ENGINE_FAIL": 1 << 0, # motor 1
|
||||
})
|
||||
|
||||
while self.get_sim_time_cached() < tstart + holdtime:
|
||||
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||
|
@ -3285,8 +3288,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Killing motor %u (%u%%)" %
|
||||
(fail_servo+1, fail_mul))
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_FAIL": fail_servo,
|
||||
"SIM_ENGINE_MUL": fail_mul,
|
||||
"SIM_ENGINE_FAIL": 1 << fail_servo,
|
||||
})
|
||||
failed = True
|
||||
|
||||
|
@ -3345,10 +3348,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
raise NotAchievedException("Vehicle is descending")
|
||||
|
||||
self.progress("Fixing motors")
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_FAIL": 0,
|
||||
"SIM_ENGINE_MUL": 1.0,
|
||||
})
|
||||
self.set_parameter("SIM_ENGINE_FAIL", 0)
|
||||
|
||||
self.do_RTL()
|
||||
|
||||
|
@ -4170,8 +4170,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.takeoff(40)
|
||||
self.set_rc(9, 1500)
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_MUL": 0,
|
||||
"SIM_ENGINE_FAIL": 1,
|
||||
"SIM_ENGINE_FAIL": 1 << 1, # motor 2
|
||||
})
|
||||
self.wait_statustext('BANG! Parachute deployed', timeout=60)
|
||||
self.set_rc(9, 1000)
|
||||
|
@ -4184,8 +4183,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.takeoff(loiter_alt, mode='LOITER')
|
||||
self.set_rc(9, 1100)
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_MUL": 0,
|
||||
"SIM_ENGINE_FAIL": 1,
|
||||
"SIM_ENGINE_FAIL": 1 << 1, # motor 2
|
||||
})
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + 5:
|
||||
|
@ -12024,8 +12022,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.context_push()
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.set_parameters({
|
||||
"SIM_ENGINE_FAIL": 1,
|
||||
"SIM_ENGINE_MUL": 0.5,
|
||||
"SIM_ENGINE_FAIL": 1 << 1, # motor 2
|
||||
"FLIGHT_OPTIONS": 4,
|
||||
})
|
||||
|
||||
|
|
|
@ -767,8 +767,7 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
|||
"Q_WVANE_ENABLE": 1,
|
||||
"Q_WVANE_GAIN": 1,
|
||||
"STICK_MIXING": 0,
|
||||
"Q_FWD_THR_USE": 2,
|
||||
"SIM_ENGINE_FAIL": 2}) # we want to fail the forward thrust motor only
|
||||
"Q_FWD_THR_USE": 2})
|
||||
|
||||
self.takeoff(10, mode="QLOITER")
|
||||
self.set_rc(2, 1000)
|
||||
|
@ -785,7 +784,7 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
|||
self.set_rc(2, 1500)
|
||||
self.delay_sim_time(5)
|
||||
loc1 = self.mav.location()
|
||||
self.set_parameter("SIM_ENGINE_MUL", 0) # simulate a complete loss of forward motor thrust
|
||||
self.set_parameter("SIM_ENGINE_FAIL", 1 << 2) # simulate a complete loss of forward motor thrust
|
||||
self.delay_sim_time(20)
|
||||
self.change_mode('QLAND')
|
||||
self.wait_disarmed(timeout=60)
|
||||
|
@ -1475,7 +1474,10 @@ class AutoTestQuadPlane(vehicle_test_suite.TestSuite):
|
|||
(p, new_values[p], threshold))
|
||||
|
||||
self.progress("ensure we are not overtuned")
|
||||
self.set_parameter('SIM_ENGINE_MUL', 0.9)
|
||||
self.set_parameters({
|
||||
'SIM_ENGINE_MUL': 0.9,
|
||||
'SIM_ENGINE_FAIL': 1 << 0,
|
||||
})
|
||||
|
||||
self.delay_sim_time(5)
|
||||
|
||||
|
|
Loading…
Reference in New Issue