mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
Revert "autotest: use SIM_STATE (common.xml) instead of SIMSTATE (ardupilotmega.xml)"
This reverts commit 540a56adb8
.
Polling this message caused issues on reboot - shouldn't be a problem
but is.
Retrying that showed that the Tracker GUIDED test failed reliably due to
a yaw problem.
This commit is contained in:
parent
231ee84ab9
commit
abb6521127
@ -2520,14 +2520,13 @@ class AutoTestCopter(AutoTest):
|
|||||||
while True:
|
while True:
|
||||||
if self.get_sim_time_cached() - tstart > 200:
|
if self.get_sim_time_cached() - tstart > 200:
|
||||||
raise NotAchievedException("Did not disarm")
|
raise NotAchievedException("Did not disarm")
|
||||||
# self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
||||||
# blocking=True)
|
blocking=True)
|
||||||
# print("gpi=%s" % str(gpi))
|
# print("gpi=%s" % str(gpi))
|
||||||
# self.mav.recv_match(type='SIM_STATE',
|
self.mav.recv_match(type='SIMSTATE',
|
||||||
# blocking=True)
|
blocking=True)
|
||||||
# print("ss=%s" % str(ss))
|
# print("ss=%s" % str(ss))
|
||||||
# wait for RTL disarm:
|
# wait for RTL disarm:
|
||||||
self.wait_heartbeat()
|
|
||||||
if not self.armed():
|
if not self.armed():
|
||||||
break
|
break
|
||||||
|
|
||||||
|
@ -1461,13 +1461,13 @@ class AutoTestPlane(AutoTest):
|
|||||||
|
|
||||||
# these are ordered to bookend the list with timestamps (which
|
# these are ordered to bookend the list with timestamps (which
|
||||||
# both attitude messages have):
|
# both attitude messages have):
|
||||||
get_names = ['ATTITUDE', 'SIM_STATE', 'AHRS2', 'ATTITUDE_QUATERNION']
|
get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']
|
||||||
msgs = self.get_messages_frame(get_names)
|
msgs = self.get_messages_frame(get_names)
|
||||||
|
|
||||||
for get_name in get_names:
|
for get_name in get_names:
|
||||||
self.progress("%s: %s" % (get_name, msgs[get_name]))
|
self.progress("%s: %s" % (get_name, msgs[get_name]))
|
||||||
|
|
||||||
simstate = msgs['SIM_STATE']
|
simstate = msgs['SIMSTATE']
|
||||||
attitude = msgs['ATTITUDE']
|
attitude = msgs['ATTITUDE']
|
||||||
ahrs2 = msgs['AHRS2']
|
ahrs2 = msgs['AHRS2']
|
||||||
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
|
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
|
||||||
@ -1612,7 +1612,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
def validate_global_position_int_against_simstate(mav, m):
|
def validate_global_position_int_against_simstate(mav, m):
|
||||||
if m.get_type() == 'GLOBAL_POSITION_INT':
|
if m.get_type() == 'GLOBAL_POSITION_INT':
|
||||||
self.gpi = m
|
self.gpi = m
|
||||||
elif m.get_type() == 'SIM_STATE':
|
elif m.get_type() == 'SIMSTATE':
|
||||||
self.simstate = m
|
self.simstate = m
|
||||||
if self.gpi is None:
|
if self.gpi is None:
|
||||||
return
|
return
|
||||||
|
@ -2713,18 +2713,18 @@ class AutoTest(ABC):
|
|||||||
|
|
||||||
def sim_location(self):
|
def sim_location(self):
|
||||||
"""Return current simulator location."""
|
"""Return current simulator location."""
|
||||||
m = self.poll_message('SIM_STATE')
|
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
|
||||||
return mavutil.location(m.lat*1.0e-7,
|
return mavutil.location(m.lat*1.0e-7,
|
||||||
m.lon*1.0e-7,
|
m.lng*1.0e-7,
|
||||||
m.alt,
|
0,
|
||||||
math.degrees(m.yaw))
|
math.degrees(m.yaw))
|
||||||
|
|
||||||
def sim_location_int(self):
|
def sim_location_int(self):
|
||||||
"""Return current simulator location."""
|
"""Return current simulator location."""
|
||||||
m = self.poll_message('SIM_STATE')
|
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
|
||||||
return mavutil.location(m.lat,
|
return mavutil.location(m.lat,
|
||||||
m.lon,
|
m.lng,
|
||||||
m.alt,
|
0,
|
||||||
math.degrees(m.yaw))
|
math.degrees(m.yaw))
|
||||||
|
|
||||||
def save_wp(self, ch=7):
|
def save_wp(self, ch=7):
|
||||||
@ -7194,8 +7194,10 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
# wait until we definitely know where we are:
|
# wait until we definitely know where we are:
|
||||||
self.poll_home_position(timeout=120)
|
self.poll_home_position(timeout=120)
|
||||||
|
|
||||||
ss = self.poll_message("SIM_STATE")
|
ss = self.mav.recv_match(type='SIMSTATE', blocking=True, timeout=1)
|
||||||
self.progress("Got SIM_STATE (%s)" % str(ss))
|
if ss is None:
|
||||||
|
raise NotAchievedException("Did not get SIMSTATE")
|
||||||
|
self.progress("Got SIMSTATE (%s)" % str(ss))
|
||||||
|
|
||||||
self.run_cmd(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
self.run_cmd(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
|
||||||
math.degrees(ss.yaw), # param1
|
math.degrees(ss.yaw), # param1
|
||||||
|
Loading…
Reference in New Issue
Block a user