mirror of https://github.com/ArduPilot/ardupilot
autotest: add basic sensor-health test for optical flow in Rover
This commit is contained in:
parent
e1a1d15f62
commit
75614b8c3b
|
@ -6901,6 +6901,20 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.set_parameter('FENCE_TYPE', 6)
|
||||
self.assert_prearm_failure('vehicle outside fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
|
||||
def OpticalFlow(self):
|
||||
'''lightly test OpticalFlow'''
|
||||
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, False, False, False, verbose=True)
|
||||
|
||||
self.context_push()
|
||||
self.set_parameter("SIM_FLOW_ENABLE", 1)
|
||||
self.set_parameter("FLOW_TYPE", 10)
|
||||
|
||||
self.reboot_sitl()
|
||||
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, True, True, True, verbose=True)
|
||||
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestRover, self).tests()
|
||||
|
@ -6991,6 +7005,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.MissionRetransfer,
|
||||
self.FenceFullAndPartialTransfer,
|
||||
self.MissionPolyEnabledPreArm,
|
||||
self.OpticalFlow,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
|
Loading…
Reference in New Issue