mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
autotest: add tests for compass prearms
This commit is contained in:
parent
f1eec8482b
commit
2271827c9d
@ -12907,6 +12907,27 @@ switch value'''
|
|||||||
if ex is not None:
|
if ex is not None:
|
||||||
raise ex
|
raise ex
|
||||||
|
|
||||||
|
def CompassPrearms(self):
|
||||||
|
'''test compass prearm checks'''
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
# XY are checked specially:
|
||||||
|
for axis in 'X', 'Y': # ArduPilot only checks these two axes
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameter(f"COMPASS_OFS2_{axis}", 1000)
|
||||||
|
self.assert_prearm_failure("Compasses inconsistent")
|
||||||
|
self.context_pop()
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
|
||||||
|
# now test the total anglular difference:
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameters({
|
||||||
|
"COMPASS_OFS2_X": 1000,
|
||||||
|
"COMPASS_OFS2_Y": -1000,
|
||||||
|
"COMPASS_OFS2_Z": -10000,
|
||||||
|
})
|
||||||
|
self.assert_prearm_failure("Compasses inconsistent")
|
||||||
|
self.context_pop()
|
||||||
|
|
||||||
def AHRS_ORIENTATION(self):
|
def AHRS_ORIENTATION(self):
|
||||||
'''test AHRS_ORIENTATION parameter works'''
|
'''test AHRS_ORIENTATION parameter works'''
|
||||||
self.context_push()
|
self.context_push()
|
||||||
|
@ -6355,6 +6355,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
self.InitialMode,
|
self.InitialMode,
|
||||||
self.DriveMaxRCIN,
|
self.DriveMaxRCIN,
|
||||||
self.NoArmWithoutMissionItems,
|
self.NoArmWithoutMissionItems,
|
||||||
|
self.CompassPrearms,
|
||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user