autotest: augment yaw calibration test to attempt as CMD_INT

This commit is contained in:
Peter Barker 2023-05-29 10:57:28 +10:00 committed by Andrew Tridgell
parent db217d47fa
commit 4fc5b5bdb6
1 changed files with 13 additions and 1 deletions

View File

@ -9295,13 +9295,25 @@ Also, ignores heartbeats not from our target system'''
0, # param2 0, # param2
0, # param3 0, # param3
0, # param4 0, # param4
0, # param5 0, # param5
0, # param6 0, # param6
0 # param7 0 # param7
) )
self.verify_parameter_values(wanted) self.verify_parameter_values(wanted)
# run same command but as command_int:
self.zero_mag_offset_parameters()
self.run_cmd_int(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
math.degrees(ss.yaw), # param1
0, # param2
0, # param3
0, # param4
0, # param5
0, # param6
0 # param7
)
self.verify_parameter_values(wanted)
self.progress("Rebooting and making sure we could arm with these values") self.progress("Rebooting and making sure we could arm with these values")
self.reboot_sitl() self.reboot_sitl()
self.wait_ready_to_arm(timeout=60) self.wait_ready_to_arm(timeout=60)