Tools: autotest: provide description of exceptions in constructors

This commit is contained in:
Peter Barker 2018-10-18 13:55:16 +11:00 committed by Peter Barker
parent b276034c60
commit a66cc52573
4 changed files with 154 additions and 181 deletions

View File

@ -197,7 +197,7 @@ class AutoTestRover(AutoTest):
num_wp = self.save_mission_to_file(
os.path.join(testdir, "rover-ch7_mission.txt"))
if num_wp != 6:
raise NotAchievedException()
raise NotAchievedException("Did not get 6 waypoints")
# TODO: actually drive the mission
@ -386,8 +386,7 @@ class AutoTestRover(AutoTest):
if time.time() - start > 10:
break
self.progress("banner not received")
raise MsgRcvTimeoutException()
raise MsgRcvTimeoutException("banner not received")
def drive_brake_get_stopping_distance(self, speed):
# measure our stopping distance:
@ -444,12 +443,11 @@ class AutoTestRover(AutoTest):
delta = distance_without_brakes - distance_with_brakes
if delta < distance_without_brakes * 0.05: # 5% isn't asking for much
self.progress("Brakes have negligible effect"
"(with=%0.2fm without=%0.2fm delta=%0.2fm)" %
(distance_with_brakes,
distance_without_brakes,
delta))
raise NotAchievedException()
raise NotAchievedException("""
Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
""" % (distance_with_brakes,
distance_without_brakes,
delta))
self.progress(
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
@ -470,13 +468,14 @@ class AutoTestRover(AutoTest):
blocking=True,
timeout=0.1)
if m is None:
self.progress("Did not receive NAV_CONTROLLER_OUTPUT message")
raise MsgRcvTimeoutException()
raise MsgRcvTimeoutException(
"Did not receive NAV_CONTROLLER_OUTPUT message")
wp_dist_min = 5
if m.wp_dist < wp_dist_min:
self.progress("Did not start at least 5 metres from destination")
raise PreconditionFailedException()
raise PreconditionFailedException(
"Did not start at least %u metres from destination" %
(wp_dist_min))
self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %
(m.wp_dist, wp_dist_min,))
@ -487,9 +486,9 @@ class AutoTestRover(AutoTest):
home_distance = self.get_distance(HOME, pos)
home_distance_max = 5
if home_distance > home_distance_max:
self.progress("Did not get home (%u metres distant > %u)" %
(home_distance, home_distance_max))
raise NotAchievedException()
raise NotAchievedException(
"Did not get home (%u metres distant > %u)" %
(home_distance, home_distance_max))
self.mavproxy.send('switch 6\n')
self.wait_mode('MANUAL')
self.progress("RTL Mission OK")
@ -500,8 +499,8 @@ class AutoTestRover(AutoTest):
self.mavproxy.send("relay set 0 1\n")
on = self.get_parameter("SIM_PIN_MASK")
if on == off:
self.progress("Pin mask unchanged after relay command")
raise NotAchievedException()
raise NotAchievedException(
"Pin mask unchanged after relay cmd")
self.progress("Pin mask changed after relay command")
def test_setting_modes_via_mavproxy_switch(self):

View File

@ -214,13 +214,13 @@ class AutoTestCopter(AutoTest):
alt_delta = math.fabs(m.alt - start_altitude)
self.progress("Loiter Dist: %.2fm, alt:%u" % (delta, m.alt))
if alt_delta > maxaltchange:
self.progress("Loiter alt shifted %u meters (> limit of %u)" %
(alt_delta, maxaltchange))
raise NotAchievedException()
raise NotAchievedException(
"Loiter alt shifted %u meters (> limit %u)" %
(alt_delta, maxaltchange))
if delta > maxdistchange:
self.progress("Loiter shifted %u meters (> limit of %u)" %
raise NotAchievedException(
"Loiter shifted %u meters (> limit of %u)" %
(delta, maxdistchange))
raise NotAchievedException()
self.progress("Loiter OK for %u seconds" % holdtime)
def change_alt(self, alt_min, climb_throttle=1920, descend_throttle=1080):
@ -350,8 +350,11 @@ class AutoTestCopter(AutoTest):
(alt, home_distance, home))
# our post-condition is that we are disarmed:
if not self.armed():
if home == "":
raise NotAchievedException("Did not get home")
# success!
return
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Did not get home and disarm")
def fly_throttle_failsafe(self, side=60, timeout=180):
"""Fly east, Failsafe, return, land."""
@ -413,8 +416,6 @@ class AutoTestCopter(AutoTest):
self.set_rc(3, 1000)
self.arm_vehicle()
return
self.progress("Failed to land on failsafe RTL - "
"timed out after %u seconds" % timeout)
# reduce throttle
self.set_rc(3, 1100)
# switch back to stabilize mode
@ -422,7 +423,9 @@ class AutoTestCopter(AutoTest):
self.wait_mode('LAND')
self.mavproxy.send('switch 6\n') # stabilize mode
self.wait_mode('STABILIZE')
raise AutoTestTimeoutException()
raise AutoTestTimeoutException(
("Failed to land on failsafe RTL - "
"timed out after %u seconds" % timeout))
def fly_battery_failsafe(self, timeout=300):
# switch to loiter mode so that we hold position
@ -488,13 +491,13 @@ class AutoTestCopter(AutoTest):
alt_delta = math.fabs(m.alt - start_altitude)
self.progress("Loiter Dist: %.2fm, alt:%u" % (delta, m.alt))
if alt_delta > maxaltchange:
self.progress("Loiter alt shifted %u meters (> limit of %u)" %
(alt_delta, maxaltchange))
raise NotAchievedException()
raise NotAchievedException(
"Loiter alt shifted %u meters (> limit %u)" %
(alt_delta, maxaltchange))
if delta > maxdistchange:
self.progress("Loiter shifted %u meters (> limit of %u)" %
(delta, maxdistchange))
raise NotAchievedException()
raise NotAchievedException(
("Loiter shifted %u meters (> limit of %u)" %
(delta, maxdistchange)))
# restore motor 1 to 100% efficiency
self.set_parameter("SIM_ENGINE_MUL", 1.0)
@ -567,9 +570,10 @@ class AutoTestCopter(AutoTest):
self.wait_mode('LAND')
self.mavproxy.send('switch 6\n') # stabilize mode
self.wait_mode('STABILIZE')
self.progress("Fence test failed to reach home - "
"timed out after %u seconds" % timeout)
raise AutoTestTimeoutException()
self.progress()
raise AutoTestTimeoutException(
("Fence test failed to reach home - "
"timed out after %u seconds" % timeout))
# fly_alt_fence_test - fly up until you hit the fence
def fly_alt_max_fence_test(self):
@ -703,9 +707,9 @@ class AutoTestCopter(AutoTest):
moved_distance = self.get_distance(curr_pos, start_pos)
self.progress("Alt: %u Moved: %.0f" % (alt, moved_distance))
if moved_distance > max_distance:
self.progress("Moved over %u meters, Failed!" %
max_distance)
raise NotAchievedException()
self.progress()
raise NotAchievedException(
"Moved over %u meters, Failed!" % max_distance)
# disable gps glitch
if glitch_current != -1:
@ -747,8 +751,7 @@ class AutoTestCopter(AutoTest):
global num_wp
num_wp = self.load_mission("copter_glitch_mission.txt")
if not num_wp:
self.progress("load copter_glitch_mission failed")
raise NotAchievedException()
raise NotAchievedException("load copter_glitch_mission failed")
# turn on simulator display of gps and actual position
if self.use_map:
@ -809,9 +812,9 @@ class AutoTestCopter(AutoTest):
dist_to_home = self.get_distance(HOME, pos)
while dist_to_home > 5:
if self.get_sim_time() > (tstart + timeout):
self.progress("GPS Glitch testing failed"
"- exceeded timeout %u seconds" % timeout)
raise AutoTestTimeoutException()
raise AutoTestTimeoutException(
("GPS Glitch testing failed"
"- exceeded timeout %u seconds" % timeout))
self.mav.recv_match(type='VFR_HUD', blocking=True)
pos = self.mav.location()
@ -988,8 +991,8 @@ class AutoTestCopter(AutoTest):
self.progress("%0.1f: Low Speed: %f" %
(self.get_sim_time_cached() - tstart, spd))
if spd > 8:
self.progress("Speed should be limited by EKF optical flow limits")
raise NotAchievedException()
raise NotAchievedException(("Speed should be limited by"
"EKF optical flow limits"))
self.progress("Moving higher")
self.change_alt(60)
@ -1028,9 +1031,9 @@ class AutoTestCopter(AutoTest):
# near enough for now:
return
self.progress("AUTOTUNE failed (%u seconds)" %
(self.get_sim_time() - tstart))
raise NotAchievedException()
self.progress()
raise NotAchievedException("AUTOTUNE failed (%u seconds)" %
(self.get_sim_time() - tstart))
# fly_auto_test - fly mission which tests a significant number of commands
def fly_auto_test(self):
@ -1040,8 +1043,7 @@ class AutoTestCopter(AutoTest):
global num_wp
num_wp = self.load_mission("copter_mission.txt")
if not num_wp:
self.progress("load copter_mission failed")
raise NotAchievedException()
raise NotAchievedException("load copter_mission failed")
self.progress("test: Fly a mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
@ -1075,8 +1077,7 @@ class AutoTestCopter(AutoTest):
global num_wp
num_wp = self.load_mission("copter_AVC2013_mission.txt")
if not num_wp:
self.progress("load copter_AVC2013_mission failed")
raise NotAchievedException()
raise NotAchievedException("load copter_AVC2013_mission failed")
self.progress("Fly AVC mission from 1 to %u" % num_wp)
self.mavproxy.send('wp set 1\n')
@ -1200,8 +1201,7 @@ class AutoTestCopter(AutoTest):
self.progress("----")
if alt_delta < -20:
self.progress("Vehicle is descending")
raise NotAchievedException()
raise NotAchievedException("Vehicle is descending")
self.set_parameter("SIM_ENGINE_FAIL", 0)
self.set_parameter("SIM_ENGINE_MUL", 1.0)
@ -1265,7 +1265,7 @@ class AutoTestCopter(AutoTest):
break
if self.get_sim_time() - tstart > 10:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Did not get non-zero lat")
self.takeoff()
self.set_rc(1, 1600)
@ -1281,7 +1281,7 @@ class AutoTestCopter(AutoTest):
break
if self.get_sim_time() - tstart > 100:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Vicon showed no movement")
# recenter controls:
self.set_rc(1, 1500)
@ -1291,7 +1291,7 @@ class AutoTestCopter(AutoTest):
tstart = self.get_sim_time()
while True:
if self.get_sim_time() - tstart > 200:
raise NotAchievedException()
raise NotAchievedException("Did not disarm")
self.mav.recv_match(type='GLOBAL_POSITION_INT',
blocking=True)
# print("gpi=%s" % str(gpi))
@ -1340,7 +1340,7 @@ class AutoTestCopter(AutoTest):
while self.armed(): # we RTL at end of mission
now = self.get_sim_time_cached()
if now - tstart > 120:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Did not disarm as expected")
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True)
if ((now - last_mission_current_msg) > 1 or
m.seq != last_seq):
@ -1364,7 +1364,7 @@ class AutoTestCopter(AutoTest):
self.progress("Stopped for %u seconds (want >=%u seconds)" %
(calculated_delay, want_delay))
if calculated_delay < want_delay:
raise NotAchievedException()
raise NotAchievedException("Did not delay for long enough")
except Exception as e:
self.progress("Exception caught")
@ -1462,7 +1462,8 @@ class AutoTestCopter(AutoTest):
tstart = self.get_sim_time()
while True:
if self.get_sim_time_cached() - tstart > 3:
raise NotAchievedException()
raise NotAchievedException(
"Did not receive MISSION_REQUEST")
self.mav.mav.mission_write_partial_list_send(1,
1,
seq,
@ -1481,9 +1482,9 @@ class AutoTestCopter(AutoTest):
# we have to change out the delay time...
now = self.mav.messages["SYSTEM_TIME"]
if now is None:
raise PreconditionFailedException()
raise PreconditionFailedException("Never got SYSTEM_TIME")
if now.time_unix_usec == 0:
raise PreconditionFailedException()
raise PreconditionFailedException("system time is zero")
(hours, mins, secs, ms) = self.calc_delay(
now.time_unix_usec/1000000)
@ -1543,7 +1544,7 @@ class AutoTestCopter(AutoTest):
while self.armed(): # we RTL at end of mission
now = self.get_sim_time()
if now - tstart > 120:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Did not disarm as expected")
m = self.mav.recv_match(type='MISSION_CURRENT', blocking=True)
self.progress("MISSION_CURRENT.seq=%u" % (m.seq,))
if m.seq == delay_item_seq:
@ -1558,8 +1559,7 @@ class AutoTestCopter(AutoTest):
self.progress("Stopped for %u seconds (want >=%u seconds)" %
(calculated_delay, delay_for_seconds))
if error > 2:
self.progress("Too far outside expectations")
raise NotAchievedException()
raise NotAchievedException("delay outside expectations")
except Exception as e:
self.progress("Exception caught")
@ -1612,13 +1612,13 @@ class AutoTestCopter(AutoTest):
took_off = True
delta_time = now - reset_at
if abs(delta_time - delay_for_seconds) > 2:
self.progress("Did not take off on time "
"measured=%f want=%f" %
(delta_time, delay_for_seconds))
raise NotAchievedException()
raise NotAchievedException((
"Did not take off on time "
"measured=%f want=%f" %
(delta_time, delay_for_seconds)))
if not took_off:
raise NotAchievedException()
raise NotAchievedException("Did not take off")
except Exception as e:
self.progress("Exception caught")
@ -1731,7 +1731,7 @@ class AutoTestCopter(AutoTest):
tstart = self.get_sim_time()
while True:
if self.get_sim_time() - tstart > 200:
raise NotAchievedException()
raise NotAchievedException("Did not move far enough")
# send a position-control command
self.mav.mav.set_position_target_global_int_send(
0, # timestamp
@ -1789,6 +1789,7 @@ class AutoTestCopter(AutoTest):
self.progress("Setting up RC parameters")
self.set_rc_default()
self.set_rc(3, 1000)
self.run_test("Fly Nav Delay (takeoff)",
self.fly_nav_takeoff_delay_abstime)

View File

@ -184,8 +184,7 @@ class AutoTestPlane(AutoTest):
self.wait_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
raise NotAchievedException()
raise NotAchievedException("Failed to maintain altitude")
self.progress("Completed Loiter OK")
@ -214,8 +213,7 @@ class AutoTestPlane(AutoTest):
self.wait_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
raise NotAchievedException()
raise NotAchievedException("Failed to maintain altitude")
self.progress("Completed CIRCLE OK")
@ -234,8 +232,7 @@ class AutoTestPlane(AutoTest):
if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:
self.progress("Attained level flight")
return
self.progress("Failed to attain level flight")
raise NotAchievedException()
raise NotAchievedException("Failed to attain level flight")
def change_altitude(self, altitude, accuracy=30):
"""Get to a given altitude."""
@ -323,7 +320,7 @@ class AutoTestPlane(AutoTest):
state = state_roll_over
while state != state_done:
if self.get_sim_time() - tstart > 20:
raise NotAchievedException()
raise AutoTestTimeoutException("Manuevers not completed")
m = self.mav.recv_match(type='ATTITUDE',
blocking=True,
@ -347,14 +344,13 @@ class AutoTestPlane(AutoTest):
if self.get_sim_time() - hold_start > 10:
state = state_roll_back
if abs(r - target_roll_degrees) > 10:
self.progress("Failed to hold attitude")
raise NotAchievedException()
raise NotAchievedException("Failed to hold attitude")
elif state == state_roll_back:
target_roll_degrees = 0
if abs(r - target_roll_degrees) < 10:
state = state_done
else:
raise ValueError()
raise ValueError("Unknown state %s" % str(state))
self.progress("%s Roll: %f desired=%f" %
(state, r, target_roll_degrees))
@ -524,8 +520,7 @@ class AutoTestPlane(AutoTest):
self.wait_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
self.progress("Failed to maintain altitude")
raise NotAchievedException()
raise NotAchievedException("Failed to maintain altitude")
return self.wait_level_flight()
@ -584,9 +579,8 @@ class AutoTestPlane(AutoTest):
delta_time_min = 0.5
delta_time_max = 1.5
if delta_time < delta_time_min or delta_time > delta_time_max:
self.progress("Flaps Slew not working (%f seconds)" %
(delta_time,))
raise NotAchievedException()
raise NotAchievedException((
"Flaps Slew not working (%f seconds)" % (delta_time,)))
# undeploy flaps:
self.set_rc(flaps_ch, flaps_ch_min)
self.wait_servo_channel_value(servo_ch, servo_ch_min)
@ -639,25 +633,25 @@ class AutoTestPlane(AutoTest):
'''test toggling channel 12 toggles relay'''
off = self.get_parameter("SIM_PIN_MASK")
if off:
raise PreconditionFailedException()
raise PreconditionFailedException("SIM_MASK_PIN off")
self.set_rc(12, 2000)
self.mav.wait_heartbeat()
self.mav.wait_heartbeat()
on = self.get_parameter("SIM_PIN_MASK")
if not on:
raise NotAchievedException()
raise NotAchievedException("SIM_PIN_MASK doesn't reflect ON")
self.set_rc(12, 1000)
self.mav.wait_heartbeat()
self.mav.wait_heartbeat()
off = self.get_parameter("SIM_PIN_MASK")
if off:
raise NotAchievedException()
raise NotAchievedException("SIM_PIN_MASK doesn't reflect OFF")
def test_rc_option_camera_trigger(self):
'''test toggling channel 12 takes picture'''
x = self.mav.messages.get("CAMERA_FEEDBACK", None)
if x is not None:
raise PreconditionFailedException()
raise PreconditionFailedException("Receiving CAMERA_FEEDBACK?!")
self.set_rc(12, 2000)
tstart = self.get_sim_time()
while self.get_sim_time() - tstart < 10:
@ -667,7 +661,7 @@ class AutoTestPlane(AutoTest):
self.mav.wait_heartbeat()
self.set_rc(12, 1000)
if x is None:
raise NotAchievedException()
raise NotAchievedException("No CAMERA_FEEDBACK message received")
def autotest(self):
"""Autotest ArduPlane in SITL."""

View File

@ -213,7 +213,7 @@ class AutoTest(ABC):
break
if self.get_sim_time() - tstart > 10:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("SYSTEM_TIME not received")
m = self.mav.recv_match(type='SYSTEM_TIME',
blocking=True,
@ -435,8 +435,8 @@ class AutoTest(ABC):
if delta > self.max_set_rc_timeout:
self.max_set_rc_timeout = delta
return True
self.progress("Failed to send RC commands to channel %s" % str(chan))
raise SetRCTimeout()
raise SetRCTimeout((
"Failed to send RC commands to channel %s" % str(chan)))
def set_throttle_zero(self):
"""Set throttle to zero."""
@ -507,8 +507,7 @@ class AutoTest(ABC):
if self.mav.motors_armed():
self.progress("Motors ARMED")
return True
self.progress("Unable to ARM with mavlink")
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Unable to ARM with mavlink")
def disarm_vehicle(self, timeout=20):
"""Disarm vehicle with mavlink disarm message."""
@ -528,8 +527,7 @@ class AutoTest(ABC):
if not self.mav.motors_armed():
self.progress("Motors DISARMED")
return True
self.progress("Unable to DISARM with mavlink")
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Unable to DISARM with mavlink")
def mavproxy_arm_vehicle(self):
"""Arm vehicle with mavlink arm message send from MAVProxy."""
@ -654,9 +652,8 @@ class AutoTest(ABC):
if self.should_fetch_all_for_parameter_change(name.upper()) and value != 0:
self.fetch_parameters()
return
self.progress("Param fetch returned incorrect value (%s) vs (%s)"
raise ValueError("Param fetch returned incorrect value (%s) vs (%s)"
% (returned_value, value))
raise ValueError()
def get_parameter(self, name, retry=1, timeout=60):
"""Get parameters from vehicle."""
@ -716,7 +713,8 @@ class AutoTest(ABC):
self.progress("ACK received: %s" % str(m))
if m.command == command:
if m.result != want_result:
raise ValueError()
raise ValueError("Expected %s got %s" % (command,
m.command))
break
#################################################
@ -779,21 +777,20 @@ class AutoTest(ABC):
if m is not None:
self.progress("AUTOPILOT_VERSION received")
return
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("No AUTOPILOT_VERSION received")
def get_mode_from_mode_mapping(self, mode):
"""Validate and return the mode number from a string or int."""
mode_map = self.mav.mode_mapping()
if mode_map is None:
raise ErrorException()
raise ErrorException("No mode map")
if isinstance(mode, str):
if mode in mode_map:
return mode_map.get(mode)
if mode in mode_map.values():
return mode
self.progress("Unknown mode '%s'" % mode)
self.progress("Available modes '%s'" % mode_map)
raise ErrorException()
raise ErrorException("Unknown mode '%s'" % mode)
def do_set_mode_via_command_long(self, mode, timeout=30):
"""Set mode with a command long message."""
@ -803,7 +800,7 @@ class AutoTest(ABC):
while True:
remaining = timeout - (self.get_sim_time_cached() - tstart)
if remaining <= 0:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Failed to change mode")
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MODE,
base_mode,
custom_mode,
@ -815,9 +812,9 @@ class AutoTest(ABC):
)
m = self.mav.recv_match(type='HEARTBEAT',
blocking=True,
timeout=remaining)
timeout=5)
if m is None:
raise ErrorException()
raise ErrorException("Heartbeat not received")
if m.custom_mode == custom_mode:
return
@ -829,14 +826,14 @@ class AutoTest(ABC):
while True:
remaining = timeout - (self.get_sim_time_cached() - tstart)
if remaining <= 0:
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Failed to change mode")
self.mavproxy.send("long DO_SET_MODE %u %u\n" %
(base_mode, custom_mode))
m = self.mav.recv_match(type='HEARTBEAT',
blocking=True,
timeout=remaining)
timeout=5)
if m is None:
raise ErrorException()
raise ErrorException("Did not receive heartbeat")
if m.custom_mode == custom_mode:
return True
@ -901,7 +898,7 @@ class AutoTest(ABC):
)
while True:
if self.get_sim_time() - tstart > 200:
raise NotAchievedException()
raise NotAchievedException("Did not achieve heading")
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
self.progress("heading=%f want=%f" % (m.heading, heading))
if m.heading == heading:
@ -943,8 +940,7 @@ class AutoTest(ABC):
if alt >= alt_min and alt <= alt_max:
self.progress("Altitude OK")
return True
self.progress("Failed to attain altitude range")
raise WaitAltitudeTimout()
raise WaitAltitudeTimout("Failed to attain altitude range")
def wait_groundspeed(self, gs_min, gs_max, timeout=30):
"""Wait for a given ground speed range."""
@ -960,8 +956,7 @@ class AutoTest(ABC):
last_print = self.get_sim_time_cached();
if m.groundspeed >= gs_min and m.groundspeed <= gs_max:
return True
self.progress("Failed to attain groundspeed range")
raise WaitGroundSpeedTimeout()
raise WaitGroundSpeedTimeout("Failed to attain groundspeed range")
def wait_roll(self, roll, accuracy, timeout=30):
"""Wait for a given roll in degrees."""
@ -975,8 +970,7 @@ class AutoTest(ABC):
if math.fabs(r - roll) <= accuracy:
self.progress("Attained roll %d" % roll)
return True
self.progress("Failed to attain roll %d" % roll)
raise WaitRollTimeout()
raise WaitRollTimeout("Failed to attain roll %d" % roll)
def wait_pitch(self, pitch, accuracy, timeout=30):
"""Wait for a given pitch in degrees."""
@ -990,8 +984,7 @@ class AutoTest(ABC):
if math.fabs(p - pitch) <= accuracy:
self.progress("Attained pitch %d" % pitch)
return True
self.progress("Failed to attain pitch %d" % pitch)
raise WaitPitchTimeout()
raise WaitPitchTimeout("Failed to attain pitch %d" % pitch)
def wait_heading(self, heading, accuracy=5, timeout=30):
"""Wait for a given heading."""
@ -1011,8 +1004,7 @@ class AutoTest(ABC):
if math.fabs(m.heading - heading) <= accuracy:
self.progress("Attained heading %u" % heading)
return True
self.progress("Failed to attain heading %u" % heading)
raise WaitHeadingTimeout()
raise WaitHeadingTimeout("Failed to attain heading %u" % heading)
def wait_distance(self, distance, accuracy=5, timeout=30):
"""Wait for flight of a given distance."""
@ -1030,11 +1022,10 @@ class AutoTest(ABC):
self.progress("Attained distance %.2f meters OK" % delta)
return True
if delta > (distance + accuracy):
self.progress("Failed distance - overshoot delta=%f dist=%f"
% (delta, distance))
raise WaitDistanceTimeout()
self.progress("Failed to attain distance %u" % distance)
raise WaitDistanceTimeout()
raise WaitDistanceTimeout(
"Failed distance - overshoot delta=%f dist=%f"
% (delta, distance))
raise WaitDistanceTimeout("Failed to attain distance %u" % distance)
def wait_servo_channel_value(self, channel, value, timeout=2):
"""wait for channel to hit value"""
@ -1043,7 +1034,7 @@ class AutoTest(ABC):
while True:
remaining = timeout - (self.get_sim_time_cached() - tstart)
if remaining <= 0:
raise NotAchievedException()
raise NotAchievedException("Channel never achieved value")
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
blocking=True,
timeout=remaining)
@ -1051,7 +1042,7 @@ class AutoTest(ABC):
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
(channel_field, m_value, value))
if m_value is None:
raise ValueError() #?
raise ValueError("message has no field %s" % channel_field)
if m_value == value:
return
@ -1081,8 +1072,7 @@ class AutoTest(ABC):
continue
self.progress("Reached location (%.2f meters)" % delta)
return True
self.progress("Failed to attain location")
raise WaitLocationTimeout()
raise WaitLocationTimeout("Failed to attain location")
def wait_waypoint(self,
wpnum_start,
@ -1100,9 +1090,9 @@ class AutoTest(ABC):
self.progress("wait for waypoint ranges start=%u end=%u"
% (wpnum_start, wpnum_end))
# if start_wp != wpnum_start:
# self.progress("test: Expected start waypoint %u but got %u" %
# raise WaitWaypointTimeout("test: Expected start waypoint %u "
# "but got %u" %
# (wpnum_start, start_wp))
# raise WaitWaypointTimeout()
last_wp_msg = 0
while self.get_sim_time_cached() < tstart + timeout:
@ -1114,8 +1104,7 @@ class AutoTest(ABC):
# if we changed mode, fail
if self.mav.flightmode != mode:
self.progress('Exited %s mode' % mode)
raise WaitWaypointTimeout()
raise WaitWaypointTimeout('Exited %s mode' % mode)
if self.get_sim_time_cached() - last_wp_msg > 1:
self.progress("WP %u (wp_dist=%u Alt=%d), current_wp: %u,"
@ -1137,12 +1126,11 @@ class AutoTest(ABC):
self.progress("Reached final waypoint %u" % seq)
return True
if seq > current_wp+1:
self.progress("Failed: Skipped waypoint! Got wp %u expected %u"
% (seq, current_wp+1))
raise WaitWaypointTimeout()
self.progress("Failed: Timed out waiting for waypoint %u of %u" %
(wpnum_end, wpnum_end))
raise WaitWaypointTimeout()
raise WaitWaypointTimeout((
"Skipped waypoint! Got wp %u expected %u"
% (seq, current_wp+1)))
raise WaitWaypointTimeout("Timed out waiting for waypoint %u of %u" %
(wpnum_end, wpnum_end))
def wait_mode(self, mode, timeout=60):
"""Wait for mode to change."""
@ -1153,7 +1141,7 @@ class AutoTest(ABC):
while self.mav.flightmode != mode:
if (timeout is not None and
self.get_sim_time() > tstart + timeout):
raise WaitModeTimeout()
raise WaitModeTimeout("Did not change mode")
self.mav.wait_heartbeat()
# self.progress("heartbeat mode %s Want: %s" % (
# self.mav.flightmode, mode))
@ -1206,8 +1194,8 @@ class AutoTest(ABC):
if (current & required_value == required_value):
self.progress("EKF Flags OK")
return True
self.progress("Failed to get EKF.flags=%u" % required_value)
raise AutoTestTimeoutException()
raise AutoTestTimeoutException("Failed to get EKF.flags=%u" %
required_value)
def wait_text(self, text, timeout=20, the_function=None):
"""Wait a specific STATUS_TEXT."""
@ -1220,8 +1208,9 @@ class AutoTest(ABC):
if text.lower() in m.text.lower():
self.progress("Received expected text : %s" % m.text.lower())
return True
self.progress("Failed to received text : %s" % text.lower())
raise AutoTestTimeoutException()
self.progress()
raise AutoTestTimeoutException("Failed to received text : %s" %
text.lower())
def get_mavlink_connection_going(self):
# get a mavlink connection going
@ -1263,9 +1252,9 @@ class AutoTest(ABC):
# check for lambda: test_function without paranthesis
faulty_strings = re.findall(r"lambda\s*:\s*\w+.\w+\s*\)", f.read())
if faulty_strings:
self.progress("Syntax error in autotest lamda at : ")
print(faulty_strings)
raise ErrorException()
desc = ("Syntax error in autotest lamda at : " +
faulty_strings)
raise ErrorException(desc)
except ErrorException:
self.progress('FAILED: "%s"' % "Check for syntax mistake in autotest lambda")
exit(1)
@ -1289,25 +1278,21 @@ class AutoTest(ABC):
self.set_throttle_zero()
self.start_test("Test normal arm and disarm features")
if not self.arm_vehicle():
self.progress("Failed to ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to ARM")
if not self.disarm_vehicle():
self.progress("Failed to DISARM")
raise NotAchievedException()
raise NotAchievedException("Failed to DISARM")
if not self.mavproxy_arm_vehicle():
self.progress("Failed to ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to ARM")
if not self.mavproxy_disarm_vehicle():
self.progress("Failed to DISARM")
raise NotAchievedException()
raise NotAchievedException("Failed to DISARM")
if self.mav.mav_type != mavutil.mavlink.MAV_TYPE_SUBMARINE:
if not self.arm_motors_with_rc_input():
raise NotAchievedException()
raise NotAchievedException("Failed to arm with RC input")
if not self.disarm_motors_with_rc_input():
raise NotAchievedException()
raise NotAchievedException("Failed to disarm with RC input")
# self.arm_vehicle()
# if not self.autodisarm_motors():
# raise NotAchievedException()
# raise NotAchievedException("Did not autodisarm")
# Disable auto disarm for next test
if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR,
mavutil.mavlink.MAV_TYPE_HELICOPTER,
@ -1324,9 +1309,9 @@ class AutoTest(ABC):
self.set_parameter("RC%d_OPTION" % arming_switch, 41)
self.set_rc(arming_switch, 1000)
if not self.arm_motors_with_switch(arming_switch):
raise NotAchievedException()
raise NotAchievedException("Failed to arm with switch")
if not self.disarm_motors_with_switch(arming_switch):
raise NotAchievedException()
raise NotAchievedException("Failed to disarm with switch")
self.set_rc(arming_switch, 1000)
if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR,
mavutil.mavlink.MAV_TYPE_HELICOPTER,
@ -1338,38 +1323,32 @@ class AutoTest(ABC):
self.set_rc(3, 1800)
try:
if self.arm_vehicle():
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
except AutoTestTimeoutException():
pass
except ValueError:
pass
if self.arm_motors_with_rc_input():
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
if self.arm_motors_with_switch(arming_switch):
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
self.set_throttle_zero()
self.set_rc(arming_switch, 1000)
self.start_test("Test arming failure with ARMING_RUDDER=0")
self.set_parameter("ARMING_RUDDER", 0)
if self.arm_motors_with_rc_input():
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
self.start_test("Test disarming failure with ARMING_RUDDER=0")
self.arm_vehicle()
if self.disarm_motors_with_rc_input():
self.progress("Failed to NOT DISARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT DISARM")
self.disarm_vehicle()
self.mav.wait_heartbeat()
self.start_test("Test disarming failure with ARMING_RUDDER=1")
self.set_parameter("ARMING_RUDDER", 1)
self.arm_vehicle()
if self.disarm_motors_with_rc_input():
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
self.disarm_vehicle()
self.mav.wait_heartbeat()
self.set_parameter("ARMING_RUDDER", 2)
@ -1382,11 +1361,9 @@ class AutoTest(ABC):
self.start_test("Test arming failure with interlock enabled")
self.set_rc(interlock_channel, 2000)
if self.arm_motors_with_rc_input():
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
if self.arm_motors_with_switch(arming_switch):
self.progress("Failed to NOT ARM")
raise NotAchievedException()
raise NotAchievedException("Failed to NOT ARM")
self.disarm_vehicle()
self.mav.wait_heartbeat()
self.set_rc(arming_switch, 1000)
@ -1406,11 +1383,13 @@ class AutoTest(ABC):
timeout=remaining)
m_value = getattr(m, channel_field, None)
if m_value is None:
raise ValueError()
raise ValueError("Message has no %s field" %
channel_field)
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
(channel_field, m_value, interlock_value))
if m_value != interlock_value:
raise NotAchievedException("Motor interlock was changed while disarmed")
raise NotAchievedException(
"Motor interlock was changed while disarmed")
self.set_rc(8, 1000)
self.progress("ALL PASS")
self.context_pop()