autotest: use SIM_STATE (common.xml) instead of SIMSTATE (ardupilotmega.xml)

It is a useful superset
This commit is contained in:
Peter Barker 2021-06-28 13:33:34 +10:00 committed by Peter Barker
parent 27fcb3a100
commit 540a56adb8
3 changed files with 16 additions and 17 deletions

View File

@ -2520,13 +2520,14 @@ class AutoTestCopter(AutoTest):
while True:
if self.get_sim_time_cached() - tstart > 200:
raise NotAchievedException("Did not disarm")
self.mav.recv_match(type='GLOBAL_POSITION_INT',
blocking=True)
# self.mav.recv_match(type='GLOBAL_POSITION_INT',
# blocking=True)
# print("gpi=%s" % str(gpi))
self.mav.recv_match(type='SIMSTATE',
blocking=True)
# self.mav.recv_match(type='SIM_STATE',
# blocking=True)
# print("ss=%s" % str(ss))
# wait for RTL disarm:
self.wait_heartbeat()
if not self.armed():
break

View File

@ -1461,13 +1461,13 @@ class AutoTestPlane(AutoTest):
# these are ordered to bookend the list with timestamps (which
# both attitude messages have):
get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']
get_names = ['ATTITUDE', 'SIM_STATE', 'AHRS2', 'ATTITUDE_QUATERNION']
msgs = self.get_messages_frame(get_names)
for get_name in get_names:
self.progress("%s: %s" % (get_name, msgs[get_name]))
simstate = msgs['SIMSTATE']
simstate = msgs['SIM_STATE']
attitude = msgs['ATTITUDE']
ahrs2 = msgs['AHRS2']
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
@ -1612,7 +1612,7 @@ class AutoTestPlane(AutoTest):
def validate_global_position_int_against_simstate(mav, m):
if m.get_type() == 'GLOBAL_POSITION_INT':
self.gpi = m
elif m.get_type() == 'SIMSTATE':
elif m.get_type() == 'SIM_STATE':
self.simstate = m
if self.gpi is None:
return

View File

@ -2713,18 +2713,18 @@ class AutoTest(ABC):
def sim_location(self):
"""Return current simulator location."""
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
m = self.poll_message('SIM_STATE')
return mavutil.location(m.lat*1.0e-7,
m.lng*1.0e-7,
0,
m.lon*1.0e-7,
m.alt,
math.degrees(m.yaw))
def sim_location_int(self):
"""Return current simulator location."""
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
m = self.poll_message('SIM_STATE')
return mavutil.location(m.lat,
m.lng,
0,
m.lon,
m.alt,
math.degrees(m.yaw))
def save_wp(self, ch=7):
@ -7194,10 +7194,8 @@ Also, ignores heartbeats not from our target system'''
# wait until we definitely know where we are:
self.poll_home_position(timeout=120)
ss = self.mav.recv_match(type='SIMSTATE', blocking=True, timeout=1)
if ss is None:
raise NotAchievedException("Did not get SIMSTATE")
self.progress("Got SIMSTATE (%s)" % str(ss))
ss = self.poll_message("SIM_STATE")
self.progress("Got SIM_STATE (%s)" % str(ss))
self.run_cmd(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
math.degrees(ss.yaw), # param1