Tools: add support for ms5525 i2c sensor
This commit is contained in:
parent
7375d1949c
commit
9fb7ef915e
@ -2193,12 +2193,44 @@ class AutoTestPlane(AutoTest):
|
||||
self.progress("Mission OK")
|
||||
|
||||
def test_airspeed_drivers(self):
|
||||
self.set_parameter("ARSPD_BUS", 2)
|
||||
self.set_parameter("ARSPD_TYPE", 7) # DLVR
|
||||
airspeed_sensors = [
|
||||
("MS5525", 3, 1),
|
||||
("DLVR", 7, 2),
|
||||
]
|
||||
for (name, t, bus) in airspeed_sensors:
|
||||
self.context_push()
|
||||
if bus is not None:
|
||||
self.set_parameter("ARSPD2_BUS", bus)
|
||||
self.set_parameter("ARSPD2_TYPE", t)
|
||||
self.reboot_sitl()
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
# insert listener to compare airspeeds:
|
||||
airspeed = [None, None]
|
||||
|
||||
def check_airspeeds(mav, m):
|
||||
m_type = m.get_type()
|
||||
if (m_type == 'NAMED_VALUE_FLOAT' and
|
||||
m.name == 'AS2'):
|
||||
airspeed[1] = m.value
|
||||
elif m_type == 'VFR_HUD':
|
||||
airspeed[0] = m.airspeed
|
||||
else:
|
||||
return
|
||||
if airspeed[0] is None or airspeed[1] is None:
|
||||
return
|
||||
delta = abs(airspeed[0] - airspeed[1])
|
||||
if delta > 2:
|
||||
raise NotAchievedException("Airspeed mismatch (as1=%f as2=%f)" % (airspeed[0], airspeed[1]))
|
||||
self.install_message_hook_context(check_airspeeds)
|
||||
self.fly_mission("ap1.txt", strict=False)
|
||||
if airspeed[0] is None:
|
||||
raise NotAchievedException("Never saw an airspeed1")
|
||||
if airspeed[1] is None:
|
||||
raise NotAchievedException("Never saw an airspeed2")
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.fly_mission("ap1.txt", strict=False)
|
||||
|
||||
def fly_terrain_mission(self):
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user