mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
autotest: add baro i2c drivers autotest
This commit is contained in:
parent
78e0e52542
commit
2ae6030f0c
@ -0,0 +1,14 @@
|
|||||||
|
QGC WPL 110
|
||||||
|
0 1 0 16 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
|
||||||
|
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 20.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163501 0.000000 1
|
||||||
|
3 0 3 115 640.000000 20.000000 1.000000 1.000000 0.000000 0.000000 0.000000 1
|
||||||
|
4 0 3 19 5.000000 0.000000 0.000000 1.000000 0.000000 0.000000 20.000000 1
|
||||||
|
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.163501 0.000000 1
|
||||||
|
6 0 3 16 1.000000 0.000000 0.000000 0.000000 -35.365361 149.163995 40.000000 1
|
||||||
|
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365361 149.164563 20.000000 1
|
||||||
|
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.164531 20.000000 1
|
||||||
|
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364652 149.163995 20.000000 1
|
||||||
|
10 0 3 177 8.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
11 0 3 16 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||||
|
12 0 3 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
@ -6821,6 +6821,63 @@ class AutoTestCopter(AutoTest):
|
|||||||
if not ok:
|
if not ok:
|
||||||
raise NotAchievedException("check_replay failed")
|
raise NotAchievedException("check_replay failed")
|
||||||
|
|
||||||
|
def BaroDrivers(self):
|
||||||
|
sensors = [
|
||||||
|
("MS5611", 2),
|
||||||
|
]
|
||||||
|
for (name, bus) in sensors:
|
||||||
|
self.context_push()
|
||||||
|
if bus is not None:
|
||||||
|
self.set_parameter("BARO_EXT_BUS", bus)
|
||||||
|
self.set_parameter("BARO_PROBE_EXT", 1 << 2)
|
||||||
|
self.reboot_sitl()
|
||||||
|
self.wait_ready_to_arm()
|
||||||
|
self.arm_vehicle()
|
||||||
|
|
||||||
|
# insert listener to compare airspeeds:
|
||||||
|
messages = [None, None, None]
|
||||||
|
|
||||||
|
global count
|
||||||
|
count = 0
|
||||||
|
|
||||||
|
def check_pressure(mav, m):
|
||||||
|
global count
|
||||||
|
m_type = m.get_type()
|
||||||
|
count += 1
|
||||||
|
# if count > 500:
|
||||||
|
# if press_abs[0] is None or press_abs[1] is None:
|
||||||
|
# raise NotAchievedException("Not receiving messages")
|
||||||
|
if m_type == 'SCALED_PRESSURE3':
|
||||||
|
off = 2
|
||||||
|
elif m_type == 'SCALED_PRESSURE2':
|
||||||
|
off = 1
|
||||||
|
elif m_type == 'SCALED_PRESSURE':
|
||||||
|
off = 0
|
||||||
|
else:
|
||||||
|
return
|
||||||
|
|
||||||
|
messages[off] = m
|
||||||
|
|
||||||
|
# FIXME: make the numbers we use in the i2c simulated
|
||||||
|
# baros closer to the ones from AP_Baro_SITL
|
||||||
|
if None in messages:
|
||||||
|
return
|
||||||
|
first = messages[0]
|
||||||
|
for msg in messages[1:]:
|
||||||
|
delta_press_abs = abs(first.press_abs - msg.press_abs)
|
||||||
|
if delta_press_abs > 5:
|
||||||
|
raise NotAchievedException("Press_Abs mismatch (press1=%s press2=%s)" % (first, msg))
|
||||||
|
delta_temperature = abs(first.temperature - msg.temperature)
|
||||||
|
if delta_temperature > 1000: # that's 10-degrees leeway
|
||||||
|
raise NotAchievedException("Temperature mismatch (t1=%s t2=%s)" % (first, msg))
|
||||||
|
self.install_message_hook_context(check_pressure)
|
||||||
|
self.fly_mission("copter_mission.txt", strict=False)
|
||||||
|
if None in messages:
|
||||||
|
raise NotAchievedException("Missing a message")
|
||||||
|
|
||||||
|
self.context_pop()
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
def test_copter_gps_zero(self):
|
def test_copter_gps_zero(self):
|
||||||
# https://github.com/ArduPilot/ardupilot/issues/14236
|
# https://github.com/ArduPilot/ardupilot/issues/14236
|
||||||
self.progress("arm the vehicle and takeoff in Guided")
|
self.progress("arm the vehicle and takeoff in Guided")
|
||||||
@ -7331,6 +7388,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
"Test RangeFinder Basic Functionality",
|
"Test RangeFinder Basic Functionality",
|
||||||
self.test_rangefinder), # 23s
|
self.test_rangefinder), # 23s
|
||||||
|
|
||||||
|
("BaroDrivers",
|
||||||
|
"Test Baro Drivers",
|
||||||
|
self.BaroDrivers),
|
||||||
|
|
||||||
("SurfaceTracking",
|
("SurfaceTracking",
|
||||||
"Test Surface Tracking",
|
"Test Surface Tracking",
|
||||||
self.test_surface_tracking), # 45s
|
self.test_surface_tracking), # 45s
|
||||||
|
Loading…
Reference in New Issue
Block a user