mirror of https://github.com/ArduPilot/ardupilot
autotest: add tests to ensure we get BCN, RPM and PRX/PRXR log msgs
This commit is contained in:
parent
134e4ff705
commit
c33f6f3a8d
|
@ -6042,12 +6042,17 @@ class AutoTestCopter(AutoTest):
|
|||
self.set_parameters({
|
||||
"FENCE_ENABLE": 1,
|
||||
"PRX_TYPE": 10,
|
||||
"PRX_LOG_RAW": 1,
|
||||
"RC10_OPTION": 40, # proximity-enable
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.progress("Enabling proximity")
|
||||
self.set_rc(10, 2000)
|
||||
self.check_avoidance_corners()
|
||||
|
||||
self.assert_current_onboard_log_contains_message("PRX")
|
||||
self.assert_current_onboard_log_contains_message("PRXR")
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
@ -6386,6 +6391,8 @@ class AutoTestCopter(AutoTest):
|
|||
self.wait_groundspeed(0, 0.3, timeout=120)
|
||||
self.land_and_disarm()
|
||||
|
||||
self.assert_current_onboard_log_contains_message("BCN")
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
|
|
@ -11267,6 +11267,8 @@ switch value'''
|
|||
self.set_rc(3, 1050)
|
||||
self.wait_rpm1(timeout=10, min_rpm=200)
|
||||
|
||||
self.assert_current_onboard_log_contains_message("RPM")
|
||||
|
||||
self.drain_mav_unparsed()
|
||||
# anything with a lambda in here needs a proper test written.
|
||||
# This, at least makes sure we're getting some of each
|
||||
|
|
Loading…
Reference in New Issue