mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Tools: autotest: ensure RNFD messages emitted
This commit is contained in:
parent
a19df642a0
commit
601504e685
@ -124,12 +124,13 @@ class AutoTestCopter(AutoTest):
|
||||
relative=True,
|
||||
timeout=timeout)
|
||||
|
||||
def land(self, timeout=60):
|
||||
def land_and_disarm(self, timeout=60):
|
||||
"""Land the quad."""
|
||||
self.progress("STARTING LANDING")
|
||||
self.change_mode("LAND")
|
||||
self.wait_altitude(-5, 1, relative=True, timeout=timeout)
|
||||
self.progress("LANDING: ok!")
|
||||
self.mav.motors_disarmed_wait()
|
||||
|
||||
def hover(self, hover_throttle=1500):
|
||||
self.set_rc(3, hover_throttle)
|
||||
@ -1523,6 +1524,12 @@ class AutoTestCopter(AutoTest):
|
||||
if m is not None:
|
||||
raise NotAchievedException("Received unexpected RANGEFINDER msg")
|
||||
|
||||
# may need to force a rotation if some other test has used the
|
||||
# rangefinder...
|
||||
self.progress("Ensure no RFND messages in log")
|
||||
if self.current_onboard_log_contains_message("RFND"):
|
||||
raise NotAchievedException("Found unexpected RFND message")
|
||||
|
||||
try:
|
||||
self.set_parameter("RNGFND1_TYPE", 1)
|
||||
self.set_parameter("RNGFND1_MIN_CM", 0)
|
||||
@ -1579,12 +1586,14 @@ class AutoTestCopter(AutoTest):
|
||||
if abs(m_r.distance - m_p.relative_alt/1000) > 1:
|
||||
raise NotAchievedException("rangefinder/global position int mismatch")
|
||||
|
||||
self.land()
|
||||
self.land_and_disarm()
|
||||
|
||||
if not self.current_onboard_log_contains_message("RFND"):
|
||||
raise NotAchievedException("Did not see expected RFND message")
|
||||
|
||||
except Exception as e:
|
||||
self.progress("Exception caught")
|
||||
ex = e
|
||||
self.land()
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
|
@ -833,6 +833,59 @@ class AutoTestPlane(AutoTest):
|
||||
timeout=5)
|
||||
self.mav.motors_disarmed_wait()
|
||||
|
||||
def test_rangefinder(self):
|
||||
ex = None
|
||||
self.context_push()
|
||||
self.progress("Making sure we don't ordinarily get RANGEFINDER")
|
||||
try:
|
||||
m = self.mav.recv_match(type='RANGEFINDER',
|
||||
blocking=True,
|
||||
timeout=5)
|
||||
except Exception as e:
|
||||
print("Caught exception %s" % str(e))
|
||||
|
||||
if m is not None:
|
||||
raise NotAchievedException("Received unexpected RANGEFINDER msg")
|
||||
|
||||
try:
|
||||
self.set_parameter("RNGFND1_TYPE", 1)
|
||||
self.set_parameter("RNGFND1_MIN_CM", 0)
|
||||
self.set_parameter("RNGFND1_MAX_CM", 4000)
|
||||
self.set_parameter("RNGFND1_PIN", 0)
|
||||
self.set_parameter("RNGFND1_SCALING", 12.12)
|
||||
|
||||
self.reboot_sitl()
|
||||
|
||||
'''ensure rangefinder gives height-above-ground'''
|
||||
self.load_mission("plane-gripper-mission.txt") # borrow this
|
||||
self.mavproxy.send("wp set 1\n")
|
||||
self.change_mode('AUTO')
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
home = self.poll_home_position()
|
||||
self.wait_altitude(10, 1000, timeout=30, relative=True)
|
||||
rf = self.mav.recv_match(type="RANGEFINDER", timeout=1, blocking=True)
|
||||
if rf is None:
|
||||
raise NotAchievedException("Did not receive rangefinder message")
|
||||
gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=1)
|
||||
if gpi is None:
|
||||
raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message")
|
||||
if abs(rf.distance - gpi.relative_alt/1000.0) > 3:
|
||||
raise NotAchievedException("rangefinder alt (%s) disagrees with global-position-int.relative_alt (%s)" % (rf.distance, gpi.relative_alt/1000.0))
|
||||
self.mavproxy.expect("Auto disarmed")
|
||||
|
||||
self.progress("Ensure RFND messages in log")
|
||||
if not self.current_onboard_log_contains_message("RFND"):
|
||||
raise NotAchievedException("No RFND messages in log")
|
||||
|
||||
except Exception as e:
|
||||
self.progress("Exception caught: %s" % str(e))
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def rc_defaults(self):
|
||||
ret = super(AutoTestPlane, self).rc_defaults()
|
||||
ret[3] = 1000
|
||||
@ -875,6 +928,10 @@ class AutoTestPlane(AutoTest):
|
||||
|
||||
("AIRSPEED_AUTOCAL", "Test AIRSPEED_AUTOCAL", self.airspeed_autocal),
|
||||
|
||||
("RangeFinder",
|
||||
"Test RangeFinder Basic Functionality",
|
||||
self.test_rangefinder),
|
||||
|
||||
("LogDownLoad",
|
||||
"Log download",
|
||||
lambda: self.log_download(
|
||||
|
Loading…
Reference in New Issue
Block a user