mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: add autotest for getting yaw from moving-baseline GPS setup
This commit is contained in:
parent
2f90abd7ea
commit
99126d3cc7
@ -7328,6 +7328,23 @@ class AutoTestCopter(AutoTest):
|
||||
self.set_parameter('GPS_TYPE', 1)
|
||||
self.do_RTL()
|
||||
|
||||
def GPSForYaw(self):
|
||||
self.load_default_params_file("copter-gps-for-yaw.parm")
|
||||
self.reboot_sitl()
|
||||
ex = None
|
||||
try:
|
||||
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
|
||||
m = self.assert_receive_message("GPS2_RAW")
|
||||
self.progress(self.dump_message_verbose(m))
|
||||
if m.yaw == 0:
|
||||
raise NotAchievedException("Expected to get GPS-from-yaw")
|
||||
self.wait_ready_to_arm()
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
# a wrapper around all the 1A,1B,1C..etc tests for travis
|
||||
def tests1(self):
|
||||
ret = ([])
|
||||
@ -7945,6 +7962,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Change speed (down) during misison",
|
||||
self.WPNAV_SPEED_DN),
|
||||
|
||||
Test("GPSForYaw",
|
||||
"Moving baseline GPS yaw",
|
||||
self.GPSForYaw),
|
||||
|
||||
("DefaultIntervalsFromFiles",
|
||||
"Test setting default mavlink message intervals from files",
|
||||
self.DefaultIntervalsFromFiles),
|
||||
|
@ -9385,13 +9385,15 @@ switch value'''
|
||||
self.drain_mav()
|
||||
self.delay_sim_time(0.5)
|
||||
|
||||
def wait_gps_fix_type_gte(self, fix_type, timeout=30):
|
||||
def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT", verbose=False):
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if now - tstart > timeout:
|
||||
raise AutoTestTimeoutException("Did not get good GPS lock")
|
||||
m = self.mav.recv_match(type="GPS_RAW_INT", blocking=True, timeout=0.1)
|
||||
m = self.mav.recv_match(type=message_type, blocking=True, timeout=0.1)
|
||||
if verbose:
|
||||
self.progress("Received: %s" % str(m))
|
||||
if m is None:
|
||||
continue
|
||||
if m.fix_type >= fix_type:
|
||||
@ -11097,3 +11099,8 @@ switch value'''
|
||||
for d in defaults_filepath:
|
||||
defaults_list.append(os.path.join(testdir, d))
|
||||
return defaults_list
|
||||
|
||||
def load_default_params_file(self, filename):
|
||||
'''load a file from Tools/autotest/default_params'''
|
||||
filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename))
|
||||
self.repeatedly_apply_parameter_file(filepath)
|
||||
|
Loading…
Reference in New Issue
Block a user