Tools: act on safety switch being enabled in SITL by zeroing outputs
This commit is contained in:
parent
6b87318062
commit
522456a535
@ -9795,6 +9795,37 @@ class AutoTestCopter(AutoTest):
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
def turn_safety_x(self, value):
|
||||
self.mav.mav.set_mode_send(
|
||||
self.mav.target_system,
|
||||
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
|
||||
value)
|
||||
|
||||
def turn_safety_off(self):
|
||||
self.turn_safety_x(0)
|
||||
|
||||
def turn_safety_on(self):
|
||||
self.turn_safety_x(1)
|
||||
|
||||
def SafetySwitch(self):
|
||||
'''test safety switch behaviour'''
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.turn_safety_on()
|
||||
self.assert_prearm_failure("safety switch")
|
||||
|
||||
self.turn_safety_off()
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
self.takeoff(2, mode='LOITER')
|
||||
self.turn_safety_on()
|
||||
|
||||
self.wait_servo_channel_value(1, 0)
|
||||
self.turn_safety_off()
|
||||
|
||||
self.change_mode('LAND')
|
||||
self.wait_disarmed()
|
||||
|
||||
def GuidedYawRate(self):
|
||||
'''ensuer guided yaw rate is not affected by rate of sewt-attitude messages'''
|
||||
self.takeoff(30, mode='GUIDED')
|
||||
@ -9959,6 +9990,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.NoArmWithoutMissionItems,
|
||||
self.RPLidarA1,
|
||||
self.RPLidarA2,
|
||||
self.SafetySwitch,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
@ -2505,7 +2505,6 @@ class AutoTest(ABC):
|
||||
"SIM_RC_CHANCOUNT",
|
||||
"SIM_RICH_CTRL",
|
||||
"SIM_RICH_ENABLE",
|
||||
"SIM_SAFETY_STATE",
|
||||
"SIM_SERVO_SPEED",
|
||||
"SIM_SHIP_DSIZE",
|
||||
"SIM_SHIP_ENABLE",
|
||||
|
Loading…
Reference in New Issue
Block a user