From 80c36ecc977f92f8fc7f037664958c628580840a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 10 Sep 2022 11:24:28 +1000 Subject: [PATCH] autotest: use reflection to collect test details We had a pattern emerging of using the test name as the method name to contain the actual test. We also tended to duplicate the docstrings in the test description - or omit the docstring. This uses reflection to retrieve both the test name and the description, meaning less duplication of this information and enforcing having docstrings on the test methods. --- Tools/autotest/antennatracker.py | 28 +- Tools/autotest/arducopter.py | 1000 ++++++++++-------------------- Tools/autotest/arduplane.py | 497 +++++---------- Tools/autotest/ardusub.py | 68 +- Tools/autotest/balancebot.py | 47 +- Tools/autotest/common.py | 165 ++--- Tools/autotest/helicopter.py | 67 +- Tools/autotest/quadplane.py | 122 ++-- Tools/autotest/rover.py | 461 +++++--------- Tools/autotest/sailboat.py | 17 +- 10 files changed, 872 insertions(+), 1600 deletions(-) diff --git a/Tools/autotest/antennatracker.py b/Tools/autotest/antennatracker.py index cf58feab40..ba452956aa 100644 --- a/Tools/autotest/antennatracker.py +++ b/Tools/autotest/antennatracker.py @@ -101,6 +101,7 @@ class AutoTestTracker(AutoTest): super(AutoTestTracker, self).reboot_sitl(*args, **kwargs) def GUIDED(self): + '''Test GUIDED mode''' self.reboot_sitl() # temporary hack around control issues self.change_mode(4) # "GUIDED" self.achieve_attitude(desyaw=10, despitch=30) @@ -108,6 +109,7 @@ class AutoTestTracker(AutoTest): self.achieve_attitude(desyaw=45, despitch=10) def MANUAL(self): + '''Test MANUAL mode''' self.change_mode(0) # "MANUAL" for chan in 1, 2: for pwm in 1200, 1600, 1367: @@ -115,6 +117,7 @@ class AutoTestTracker(AutoTest): self.wait_servo_channel_value(chan, pwm) def SERVOTEST(self): + '''Test SERVOTEST mode''' self.change_mode(0) # "MANUAL" # magically changes to SERVOTEST (3) for value in 1900, 1200: @@ -143,6 +146,7 @@ class AutoTestTracker(AutoTest): self.wait_servo_channel_value(channel, value) def SCAN(self): + '''Test SCAN mode''' self.change_mode(2) # "SCAN" self.set_parameter("SCAN_SPEED_YAW", 20) for channel in 1, 2: @@ -166,24 +170,10 @@ class AutoTestTracker(AutoTest): '''return list of all tests''' ret = super(AutoTestTracker, self).tests() ret.extend([ - ("GUIDED", - "Test GUIDED mode", - self.GUIDED), - - ("MANUAL", - "Test MANUAL mode", - self.MANUAL), - - ("SERVOTEST", - "Test SERVOTEST mode", - self.SERVOTEST), - - ("NMEAOutput", - "Test AHRS NMEA Output can be read by out NMEA GPS", - self.nmea_output), - - ("SCAN", - "Test SCAN mode", - self.SCAN), + self.GUIDED, + self.MANUAL, + self.SERVOTEST, + self.NMEAOutput, + self.SCAN, ]) return ret diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 18fa565150..2928f8fe87 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -216,7 +216,7 @@ class AutoTestCopter(AutoTest): self.progress("Copter staging 50 meters east of home at 50 meters altitude In mode Alt Hold") # loiter - fly south west, then loiter within 5m position and altitude - def loiter(self, holdtime=10, maxaltchange=5, maxdistchange=5): + def ModeLoiter(self, holdtime=10, maxaltchange=5, maxdistchange=5): """Hold loiter position.""" self.takeoff(10, mode="LOITER") @@ -274,7 +274,8 @@ class AutoTestCopter(AutoTest): if m.alt <= min_alt: raise NotAchievedException("Altitude not maintained: want >%f got=%f" % (min_alt, m.alt)) - def test_mode_ALT_HOLD(self): + def ModeAltHold(self): + '''Test AltHold Mode''' self.takeoff(10, mode="ALT_HOLD") self.watch_altitude_maintained(9, 11, timeout=5) # feed in full elevator and aileron input and make sure we @@ -327,9 +328,8 @@ class AutoTestCopter(AutoTest): "FS_GCS_ENABLE": paramValue, }) - # fly a square in alt_hold mode - def fly_square(self, side=50, timeout=300): - + def RecordThenPlayMission(self, side=50, timeout=300): + '''Use switches to toggle in mission, then fly it''' self.takeoff(20, mode="ALT_HOLD") """Fly a square, flying N then E .""" @@ -467,8 +467,8 @@ class AutoTestCopter(AutoTest): raise AutoTestTimeoutException("Did not get home and disarm") - def fly_loiter_to_alt(self): - """loiter to alt""" + def LoiterToAlt(self): + """Loiter-To-Alt""" self.context_push() @@ -515,7 +515,8 @@ class AutoTestCopter(AutoTest): raise ex # Tests all actions and logic behind the radio failsafe - def fly_throttle_failsafe(self, side=60, timeout=360): + def ThrottleFailsafe(self, side=60, timeout=360): + '''Test Throttle Failsafe''' self.start_subtest("If you haven't taken off yet RC failure should be instant disarm") self.change_mode("STABILIZE") self.set_parameter("DISARM_DELAY", 0) @@ -728,7 +729,8 @@ class AutoTestCopter(AutoTest): self.reboot_sitl() # Tests all actions and logic behind the GCS failsafe - def fly_gcs_failsafe(self, side=60, timeout=360): + def GCSFailsafe(self, side=60, timeout=360): + '''Test GCS Failsafe''' try: self.test_gcs_failsafe(side=side, timeout=timeout) except Exception as ex: @@ -902,7 +904,8 @@ class AutoTestCopter(AutoTest): self.set_parameter('FS_OPTIONS', 0) self.progress("All GCS failsafe tests complete") - def test_custom_controller(self, timeout=300): + def CustomController(self, timeout=300): + '''Test Custom Controller''' self.progress("Configure custom controller parameters") self.set_parameters({ 'CC_TYPE': 2, @@ -942,7 +945,8 @@ class AutoTestCopter(AutoTest): self.progress("Custom controller test complete") # Tests all actions and logic behind the battery failsafe - def fly_battery_failsafe(self, timeout=300): + def BatteryFailsafe(self, timeout=300): + '''Fly Battery Failsafe''' self.context_push() ex = None try: @@ -1097,8 +1101,8 @@ class AutoTestCopter(AutoTest): self.progress("All Battery failsafe tests complete") - # Tests the vibration failsafe - def test_vibration_failsafe(self): + def VibrationFailsafe(self): + '''Test Vibration Failsafe''' self.context_push() # takeoff in Loiter to 20m @@ -1145,7 +1149,8 @@ class AutoTestCopter(AutoTest): self.wait_disarmed() # Tests the motor failsafe - def test_takeoff_check(self): + def TakeoffCheck(self): + '''Test takeoff check''' self.set_parameters({ "AHRS_EKF_TYPE": 10, 'SIM_ESC_TELEM': 1, @@ -1213,7 +1218,7 @@ class AutoTestCopter(AutoTest): # Tests any EK3 accel bias is subtracted from the correct IMU data def EK3AccelBias(self): - + '''Test EK3 Accel Bias data''' self.context_push() self.start_test("Test zero bias") @@ -1282,13 +1287,13 @@ class AutoTestCopter(AutoTest): self.context_pop() self.reboot_sitl() - # fly_stability_patch - fly south, then hold loiter within 5m + # StabilityPatch - fly south, then hold loiter within 5m # position and altitude and reduce 1 motor to 60% efficiency - def fly_stability_patch(self, - holdtime=30, - maxaltchange=5, - maxdistchange=10): - + def StabilityPatch(self, + holdtime=30, + maxaltchange=5, + maxdistchange=10): + '''Fly stability patch''' self.takeoff(10, mode="LOITER") # first south @@ -1414,12 +1419,14 @@ class AutoTestCopter(AutoTest): self.set_rc(2, 1500) self.do_RTL() - def fly_fence_avoid_test(self, timeout=180): + def HorizontalAvoidFence(self, timeout=180): + '''Test horizontal Avoidance fence''' self.fly_fence_avoid_test_radius_check(avoid_behave=1, timeout=timeout) self.fly_fence_avoid_test_radius_check(avoid_behave=0, timeout=timeout) # fly_fence_test - fly east until you hit the horizontal circular fence - def fly_fence_test(self, timeout=180): + def HorizontalFence(self, timeout=180): + '''Test horizontal fence''' # enable fence, disable avoidance self.set_parameters({ "FENCE_ENABLE": 1, @@ -1517,8 +1524,9 @@ class AutoTestCopter(AutoTest): "Fence test failed to reach home (%fm distance) - " "timed out after %u seconds" % (home_distance, timeout,)) - # fly_alt_max_fence_test - fly up until you hit the fence ceiling - def fly_alt_max_fence_test(self): + # MaxAltFence - fly up until you hit the fence ceiling + def MaxAltFence(self): + '''Test Max Alt Fence''' self.takeoff(10, mode="LOITER") """Hold loiter position.""" @@ -1555,7 +1563,8 @@ class AutoTestCopter(AutoTest): self.zero_throttle() # fly_alt_min_fence_test - fly down until you hit the fence floor - def fly_alt_min_fence_test(self): + def MinAltFence(self): + '''Test Min Alt Fence''' self.takeoff(30, mode="LOITER", timeout=60) # enable fence, disable avoidance @@ -1597,9 +1606,10 @@ class AutoTestCopter(AutoTest): self.zero_throttle() - def fly_fence_floor_enabled_landing(self): - """ fly_fence_floor_enabled_landing. Ensures we can initiate and complete - an RTL while the fence is enabled. """ + def FenceFloorEnabledLanding(self): + """Ensures we can initiate and complete an RTL while the fence is + enabled. + """ fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.progress("Test Landing while fence floor enabled") @@ -1635,7 +1645,7 @@ class AutoTestCopter(AutoTest): self.do_fence_disable() self.assert_fence_disabled() - def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20): + def GPSGlitchLoiter(self, timeout=30, max_distance=20): """fly_gps_glitch_loiter_test. Fly south east in loiter and test reaction to gps glitch.""" self.takeoff(10, mode="LOITER") @@ -1747,7 +1757,7 @@ class AutoTestCopter(AutoTest): # re-arming is problematic because the GPS is glitching! self.reboot_sitl() - def fly_gps_glitch_loiter_test2(self): + def GPSGlitchLoiter2(self): """test vehicle handles GPS glitch (aka EKF Reset) without twitching""" self.context_push() self.takeoff(10, mode="LOITER") @@ -1773,8 +1783,8 @@ class AutoTestCopter(AutoTest): self.context_pop() self.reboot_sitl() - # fly_gps_glitch_auto_test - fly mission and test reaction to gps glitch - def fly_gps_glitch_auto_test(self, timeout=180): + def GPSGlitchAuto(self, timeout=180): + '''fly mission and test reaction to gps glitch''' # set-up gps glitch array glitch_lat = [0.0002996, 0.0006958, @@ -1877,7 +1887,8 @@ class AutoTestCopter(AutoTest): # fly_simple - assumes the simple bearing is initialised to be # directly north flies a box with 100m west, 15 seconds north, # 50 seconds east, 15 seconds south - def fly_simple(self, side=50): + def SimpleMode(self, side=50): + '''Fly in SIMPLE mode''' self.takeoff(10, mode="LOITER") # set SIMPLE mode for all flight modes @@ -1921,7 +1932,8 @@ class AutoTestCopter(AutoTest): self.do_RTL(timeout=500) # fly_super_simple - flies a circle around home for 45 seconds - def fly_super_simple(self, timeout=45): + def SuperSimpleCircle(self, timeout=45): + '''Fly a circle in SUPER SIMPLE mode''' self.takeoff(10, mode="LOITER") # fly forward 20m @@ -1961,7 +1973,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() # fly_circle - flies a circle with 20m radius - def fly_circle(self, holdtime=36): + def ModeCircle(self, holdtime=36): + '''Fly CIRCLE mode''' # the following should not be required. But there appears to # be a physics failure in the simulation which is causing CI # to fall over a lot. -pb 202007021209 @@ -2001,8 +2014,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() - # test_mag_fail - test failover of compass in EKF - def test_mag_fail(self): + def MagFail(self): + '''test failover of compass in EKF''' # we want both EK2 and EK3 self.set_parameters({ "EK2_ENABLE": 1, @@ -2052,7 +2065,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def fly_flip(self): + def ModeFlip(self): + '''Fly Flip Mode''' ex = None try: self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 100) @@ -2106,7 +2120,7 @@ class AutoTestCopter(AutoTest): "EK3_SRC1_VELZ": 0, }) - def optical_flow(self): + def OpticalFlow(self): '''test optical low works''' self.start_subtest("Make sure no crash if no rangefinder") self.set_parameter("SIM_FLOW_ENABLE", 1) @@ -2119,8 +2133,8 @@ class AutoTestCopter(AutoTest): self.delay_sim_time(5) self.wait_statustext("Need Position Estimate", timeout=300) - # fly_optical_flow_limits - test EKF navigation limiting - def fly_optical_flow_limits(self): + def OpticalFlowLimits(self): + '''test EKF navigation limiting''' ex = None self.context_push() try: @@ -2185,8 +2199,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - # fly_optical_flow_calibration - test optical flow calibration - def fly_optical_flow_calibration(self): + def OpticalFlowCalibration(self): + '''test optical flow calibration''' ex = None self.context_push() try: @@ -2268,7 +2282,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_autotune(self): + def AutoTune(self): """Test autotune mode""" rlld = self.get_parameter("ATC_RAT_RLL_D") @@ -2306,7 +2320,7 @@ class AutoTestCopter(AutoTest): raise NotAchievedException("AUTOTUNE failed (%u seconds)" % (self.get_sim_time() - tstart)) - def fly_autotune_switch(self): + def AutoTuneSwitch(self): """Test autotune on a switch with gains being saved""" # autotune changes a set of parameters on the vehicle which @@ -2407,8 +2421,8 @@ class AutoTestCopter(AutoTest): 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): + def CopterMission(self): + '''fly mission which tests a significant number of commands''' # Fly mission #1 self.progress("# Load copter_mission") # load the waypoint count @@ -2443,8 +2457,8 @@ class AutoTestCopter(AutoTest): self.wait_disarmed() self.progress("MOTORS DISARMED OK") - # fly_auto_test using CAN GPS - fly mission which tests normal operation alongside CAN GPS - def fly_auto_test_using_can_gps(self): + def CANGPSCopterMission(self): + '''fly mission which tests normal operation alongside CAN GPS''' self.set_parameters({ "CAN_P1_DRIVER": 1, "GPS_TYPE": 9, @@ -2551,10 +2565,10 @@ class AutoTestCopter(AutoTest): self.start_sup_program(instance=0) self.context_stop_collecting('STATUSTEXT') self.context_pop() - self.fly_auto_test() + self.CopterMission() - # test takeoff altitude - def test_takeoff_alt(self): + def TakeoffAlt(self): + '''Test Takeoff command altitude''' # Test case #1 (set target altitude to relative -10m from the ground, -10m is invalid, so it is set to 1m) self.progress("Testing relative alt from the ground") self.do_takeoff_alt("copter_takeoff.txt", 1, False) @@ -2599,7 +2613,7 @@ class AutoTestCopter(AutoTest): self.wait_disarmed() self.progress("MOTORS DISARMED OK") - def fly_motor_fail(self, fail_servo=0, fail_mul=0.0, holdtime=30): + def MotorFail(self, fail_servo=0, fail_mul=0.0, holdtime=30): """Test flight with reduced motor efficiency""" # we only expect an octocopter to survive ATM: @@ -2730,7 +2744,7 @@ class AutoTestCopter(AutoTest): tend = self.get_sim_time() return tstart, tend, vfr_hud.throttle - def fly_motor_vibration(self): + def MotorVibration(self): """Test flight with motor vibration""" self.context_push() @@ -2809,7 +2823,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_vision_position(self): + def VisionPosition(self): """Disable GPS navigation, enable Vicon input.""" # scribble down a location we can set origin to: @@ -2907,7 +2921,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_body_frame_odom(self): + def BodyFrameOdom(self): """Disable GPS navigation, enable input of VISION_POSITION_DELTA.""" if self.get_parameter("AHRS_EKF_TYPE") != 3: @@ -2966,7 +2980,7 @@ class AutoTestCopter(AutoTest): if not self.current_onboard_log_contains_message("XKFD"): raise NotAchievedException("Did not find expected XKFD message") - def fly_gps_vicon_switching(self): + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -3045,7 +3059,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_rtl_speed(self): + def RTLSpeed(self): """Test RTL Speed parameters""" rtl_speed_ms = 7 wpnav_speed_ms = 4 @@ -3074,7 +3088,7 @@ class AutoTestCopter(AutoTest): self.monitor_groundspeed(wpnav_speed_ms, tolerance=0.6, timeout=5) self.do_RTL() - def fly_nav_delay(self): + def NavDelay(self): """Fly a simple mission that has a delay in it.""" self.load_mission("copter_nav_delay.txt") @@ -3121,7 +3135,8 @@ class AutoTestCopter(AutoTest): if calculated_delay < want_delay: raise NotAchievedException("Did not delay for long enough") - def test_rangefinder(self): + def RangeFinder(self): + '''Test RangeFinder Basic Functionality''' ex = None self.context_push() @@ -3203,12 +3218,13 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_terrain_spline_mission(self): + def SplineTerrain(self): + '''Test Splines and Terrain''' self.set_parameter("TERRAIN_ENABLE", 0) self.fly_mission("wp.txt") def WPNAV_SPEED(self): - '''ensure resetting WPNAV_SPEED works''' + '''ensure resetting WPNAV_SPEED during a mission works''' loc = self.poll_home_position() alt = 20 @@ -3238,7 +3254,7 @@ class AutoTestCopter(AutoTest): self.do_RTL() def WPNAV_SPEED_UP(self): - '''ensure resetting WPNAV_SPEED_UP works''' + '''Change speed (up) during mission''' items = [] @@ -3263,7 +3279,7 @@ class AutoTestCopter(AutoTest): self.do_RTL(timeout=240) def WPNAV_SPEED_DN(self): - '''ensure resetting WPNAV_SPEED_DN works''' + '''Change speed (down) during mission''' items = [] @@ -3296,7 +3312,8 @@ class AutoTestCopter(AutoTest): self.wait_waypoint(num_wp-1, num_wp-1) self.wait_disarmed() - def test_surface_tracking(self): + def SurfaceTracking(self): + '''Test Surface Tracking''' ex = None self.context_push() @@ -3404,8 +3421,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_parachute(self): - + def Parachute(self): + '''Test Parachute Functionality''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -3567,7 +3584,8 @@ class AutoTestCopter(AutoTest): self.disarm_vehicle(force=True) self.reboot_sitl() - def test_motortest(self, timeout=60): + def MotorTest(self, timeout=60): + '''Run Motor Tests''' self.start_subtest("Testing PWM output") pwm_in = 1300 # default frame is "+" - start motor of 2 is "B", which is @@ -3608,7 +3626,7 @@ class AutoTestCopter(AutoTest): self.wait_statustext("finished motor test") self.end_subtest("Testing percentage output") - def fly_precision_landing_drivers(self): + def PrecisionLanding(self): """Use PrecLand backends precision messages to land aircraft.""" self.context_push() @@ -3838,7 +3856,7 @@ class AutoTestCopter(AutoTest): timeout=1) self.progress("Received ack: %s" % str(ack)) - def fly_nav_delay_abstime(self): + def NavDelayAbsTime(self): """fly a simple mission that has a delay in it""" self.fly_nav_delay_abstime_x(87) @@ -3886,7 +3904,7 @@ class AutoTestCopter(AutoTest): if error > 2: raise NotAchievedException("delay outside expectations") - def fly_nav_takeoff_delay_abstime(self): + def NavDelayTakeoffAbsTime(self): """make sure taking off at a specific time works""" self.load_mission("copter_nav_delay_takeoff.txt") @@ -3927,9 +3945,8 @@ class AutoTestCopter(AutoTest): if not took_off: raise NotAchievedException("Did not take off") - def fly_zigzag_mode(self): + def ModeZigZag(self): '''test zigzag mode''' - # set channel 8 for zigzag savewp and recentre it self.set_parameter("RC8_OPTION", 61) @@ -4013,7 +4030,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def test_setting_modes_via_modeswitch(self): + def SetModesViaModeSwitch(self): + '''Set modes via modeswitch''' self.context_push() ex = None try: @@ -4055,7 +4073,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_setting_modes_via_auxswitch(self): + def SetModesViaAuxSwitch(self): + '''"Set modes via auxswitch"''' self.context_push() ex = None try: @@ -4500,7 +4519,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def test_gripper_mission(self): + def TestGripperMission(self): + '''Test Gripper mission items''' self.context_push() ex = None try: @@ -4522,7 +4542,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_spline_last_waypoint(self): + def SplineLastWaypoint(self): + '''Test Spline as last waypoint''' self.context_push() ex = None try: @@ -4542,7 +4563,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_manual_throttle_mode_change(self): + def ManualThrottleModeChange(self): + '''Check manual throttle mode changes denied on high throttle''' self.set_parameter("FS_GCS_ENABLE", 0) # avoid GUIDED instant disarm self.change_mode("STABILIZE") self.wait_ready_to_arm() @@ -4648,7 +4670,8 @@ class AutoTestCopter(AutoTest): 0, # stabilize pitch (unsupported) 0, 0, 0, 0) - def test_mount(self): + def Mount(self): + '''Test Camera/Antenna Mount''' ex = None self.context_push() old_srcSystem = self.mav.mav.srcSystem @@ -4990,6 +5013,7 @@ class AutoTestCopter(AutoTest): raise ex def MountYawVehicleForMountROI(self): + '''Test Camera/Antenna Mount vehicle yawing for ROI''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) @@ -5083,7 +5107,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_throw_mode(self): + def ThrowMode(self): + '''Fly Throw Mode''' # test boomerang mode: self.progress("Throwing vehicle away") self.set_parameters({ @@ -5142,7 +5167,7 @@ class AutoTestCopter(AutoTest): return freq, hover_throttle, peakdb - def fly_dynamic_notches(self): + def DynamicNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with dynamic notches") self.context_push() @@ -5213,7 +5238,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_esc_telemetry_notches(self): + def DynamicRpmNotches(self): """Use dynamic harmonic notch to control motor noise via ESC telemetry.""" self.progress("Flying with ESC telemetry driven dynamic notches") @@ -5490,16 +5515,16 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_gyro_fft_harmonic(self): + def GyroFFTHarmonic(self): """Use dynamic harmonic notch to control motor noise with harmonic matching of the first harmonic.""" self.test_gyro_fft_harmonic(False) - def fly_gyro_fft_continuous_averaging(self): + def GyroFFTContinuousAveraging(self): """Use dynamic harmonic notch with FFT averaging to control motor noise with harmonic matching of the first harmonic.""" self.test_gyro_fft_harmonic(True) - def fly_gyro_fft(self): + def GyroFFT(self): """Use dynamic harmonic notch to control motor noise.""" # basic gyro sample rate test self.progress("Flying with gyro FFT - Gyro sample rate") @@ -5650,7 +5675,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_gyro_fft_average(self): + def GyroFFTAverage(self): """Use dynamic harmonic notch to control motor noise setup via FFT averaging.""" # basic gyro sample rate test self.progress("Flying with gyro FFT harmonic - Gyro sample rate") @@ -5792,7 +5817,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_brake_mode(self): + def BrakeMode(self): + '''Fly Brake Mode''' # test brake mode self.progress("Testing brake mode") self.takeoff(10, mode="LOITER") @@ -5840,7 +5866,8 @@ class AutoTestCopter(AutoTest): if delta < 1: break - def test_altitude_types(self): + def AltTypes(self): + '''Test Different Altitude Types''' '''start by disabling GCS failsafe, otherwise we immediately disarm due to (apparently) not receiving traffic from the GCS for too long. This is probably a function of --speedup''' @@ -6006,15 +6033,17 @@ class AutoTestCopter(AutoTest): self.context_pop() self.reboot_sitl() - def test_arm_feature(self): + def ArmFeatures(self): + '''Arm features''' self.loiter_requires_position() - super(AutoTestCopter, self).test_arm_feature() + super(AutoTestCopter, self).ArmFeatures() - def test_parameter_checks(self): + def ParameterChecks(self): + '''Test Arming Parameter Checks''' self.test_parameter_checks_poscontrol("PSC") - def fly_poshold_takeoff(self): + def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() @@ -6084,8 +6113,8 @@ class AutoTestCopter(AutoTest): ret[5] = 1800 # mode switch return ret - def test_manual_control(self): - '''test manual_control mavlink message''' + def MANUAL_CONTROL(self): + '''test MANUAL_CONTROL mavlink message''' self.set_parameter("SYSID_MYGCS", self.mav.source_system) self.change_mode('STABILIZE') @@ -6201,6 +6230,7 @@ class AutoTestCopter(AutoTest): break def OBSTACLE_DISTANCE_3D(self): + '''Check round-trip behaviour of distance sensors''' self.context_push() self.set_parameters({ "SERIAL5_PROTOCOL": 1, @@ -6403,11 +6433,13 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_proximity_avoidance_test(self): + def AC_Avoidance_Proximity(self): + '''Test proximity avoidance slide behaviour''' self.fly_proximity_avoidance_test_alt_no_avoid() self.fly_proximity_avoidance_test_corners() - def fly_fence_avoidance_test(self): + def AC_Avoidance_Fence(self): + '''Test fence avoidance slide behaviour''' self.context_push() ex = None try: @@ -6436,7 +6468,8 @@ class AutoTestCopter(AutoTest): hdg=heading ) - def fly_follow_mode(self): + def ModeFollow(self): + '''Fly follow mode''' foll_ofs_x = 30 # metres self.set_parameters({ "FOLL_ENABLE": 1, @@ -6497,7 +6530,8 @@ class AutoTestCopter(AutoTest): if m.lat != 0 or m.lon != 0: return m - def fly_beacon_position(self): + def BeaconPosition(self): + '''Fly Beacon Position''' self.reboot_sitl() self.wait_ready_to_arm(require_absolute=True) @@ -6587,7 +6621,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_beacon_avoidance_test(self): + def AC_Avoidance_Beacon(self): + '''Test beacon avoidance slide behaviour''' self.context_push() ex = None try: @@ -6628,7 +6663,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_wind_baro_compensation(self): + def BaroWindCorrection(self): + '''Test wind estimation and baro position error compensation''' self.context_push() ex = None try: @@ -6727,7 +6763,8 @@ class AutoTestCopter(AutoTest): break self.progress("Got generator speed and state") - def test_richenpower(self): + def RichenPower(self): + '''Test RichenPower generator''' self.set_parameters({ "SERIAL5_PROTOCOL": 30, "SIM_RICH_ENABLE": 1, @@ -6787,7 +6824,8 @@ class AutoTestCopter(AutoTest): if not self.current_onboard_log_contains_message("GEN"): raise NotAchievedException("Did not find expected GEN message") - def test_ie24(self): + def IE24(self): + '''Test IntelligentEnergy 2.4kWh generator''' self.context_push() ex = None try: @@ -6832,7 +6870,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_aux_switch_options(self): + def AuxSwitchOptions(self): + '''Test random aux mode options''' self.set_parameter("RC7_OPTION", 58) # clear waypoints self.load_mission("copter_loiter_to_alt.txt") self.set_rc(7, 1000) @@ -6854,7 +6893,8 @@ class AutoTestCopter(AutoTest): self.wait_current_waypoint(0, timeout=10) self.set_rc(7, 1000) - def test_aux_functions_in_mission(self): + def AuxFunctionsInMission(self): + '''Test use of auxilliary functions in missions''' self.load_mission("aux_functions.txt") self.change_mode('LOITER') self.wait_ready_to_arm() @@ -6907,7 +6947,8 @@ class AutoTestCopter(AutoTest): if not self.current_onboard_log_contains_message("RFND"): raise NotAchievedException("No RFND messages in log") - def fly_proximity_mavlink_distance_sensor(self): + def MAVProximity(self): + '''Test MAVLink proximity driver''' self.start_subtest("Test mavlink proximity sensor using DISTANCE_SENSOR messages") # noqa self.context_push() ex = None @@ -7135,7 +7176,7 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_gsf(self): + def GSF(self): '''test the Gaussian Sum filter''' ex = None self.context_push() @@ -7217,7 +7258,8 @@ class AutoTestCopter(AutoTest): self.progress("mavlink rangefinder OK") self.land_and_disarm() - def fly_rangefinder_driver_maxbotix(self): + def MaxBotixI2CXL(self): + '''Test maxbotix rangefinder drivers''' ex = None try: self.context_push() @@ -7294,7 +7336,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def fly_rangefinder_drivers(self): + def RangeFinderDrivers(self): + '''Test rangefinder drivers''' self.set_parameters({ "RTL_ALT": 500, "RTL_ALT_TYPE": 1, @@ -7357,7 +7400,7 @@ class AutoTestCopter(AutoTest): self.reboot_sitl() self.fly_rangefinder_drivers_fly([x[0] for x in do_drivers]) - def fly_rangefinder_drivers_maxalt(self): + def RangeFinderDriversMaxAlt(self): '''test max-height behaviour''' # lightwareserial goes to 130m when out of range self.set_parameters({ @@ -7388,7 +7431,8 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def fly_ship_takeoff(self): + def ShipTakeoff(self): + '''Fly Simulated Ship Takeoff''' # test ship takeoff self.wait_groundspeed(0, 2) self.set_parameters({ @@ -7406,7 +7450,8 @@ class AutoTestCopter(AutoTest): # ship will have moved on, so we land on the water which isn't moving self.wait_groundspeed(0, 2) - def test_parameter_validation(self): + def ParameterValidation(self): + '''Test parameters are checked for validity''' # wait 10 seconds for initialisation self.delay_sim_time(10) self.progress("invalid; min must be less than max:") @@ -7425,6 +7470,7 @@ class AutoTestCopter(AutoTest): self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") def SensorErrorFlags(self): + '''Test we get ERR messages when sensors have issues''' self.reboot_sitl() for (param_names, param_value, expected_subsys, expected_ecode, desc) in [ @@ -7451,7 +7497,8 @@ class AutoTestCopter(AutoTest): if not success: raise NotAchievedException("Did not find %s log message" % desc) - def test_alt_estimate_prearm(self): + def AltEstimation(self): + '''Test that Alt Estimation is mandatory for ALT_HOLD''' self.context_push() ex = None try: @@ -7493,7 +7540,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_ekf_source(self): + def EKFSource(self): + '''Check EKF Source Prearms work''' self.context_push() ex = None try: @@ -7580,7 +7628,7 @@ class AutoTestCopter(AutoTest): }) old_onboard_logs = sorted(self.log_list()) - self.fly_beacon_position() + self.BeaconPosition() new_onboard_logs = sorted(self.log_list()) log_difference = [x for x in new_onboard_logs if x not in old_onboard_logs] @@ -7593,14 +7641,15 @@ class AutoTestCopter(AutoTest): }) old_onboard_logs = sorted(self.log_list()) - self.fly_optical_flow_limits() + self.OpticalFlowLimits() new_onboard_logs = sorted(self.log_list()) log_difference = [x for x in new_onboard_logs if x not in old_onboard_logs] print("log difference: %s" % str(log_difference)) return log_difference[0] - def test_gps_blending(self): + def GPSBlending(self): + '''Test GPS Blending''' '''ensure we get dataflash log messages for blended instance''' self.context_push() @@ -7674,7 +7723,8 @@ class AutoTestCopter(AutoTest): if ex is not None: raise ex - def test_callisto(self): + def Callisto(self): + '''Test Callisto''' self.customise_SITL_commandline( ["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ], model="octa-quad:@ROMFS/models/Callisto.json", @@ -7683,7 +7733,8 @@ class AutoTestCopter(AutoTest): self.takeoff(10) self.do_RTL() - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() copter_vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -7753,7 +7804,7 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def test_replay(self): + def Replay(self): '''test replay correctness''' self.progress("Building Replay") util.build_SITL('tool/Replay', clean=False, configure=False) @@ -7796,6 +7847,7 @@ class AutoTestCopter(AutoTest): raise NotAchievedException("check_replay failed") def DefaultIntervalsFromFiles(self): + '''Test setting default mavlink message intervals from files''' ex = None intervals_filepath = util.reltopdir("message-intervals-chan0.txt") self.progress("Using filepath (%s)" % intervals_filepath) @@ -7833,6 +7885,7 @@ class AutoTestCopter(AutoTest): raise ex def BaroDrivers(self): + '''Test Baro Drivers''' sensors = [ ("MS5611", 2), ] @@ -7887,7 +7940,8 @@ class AutoTestCopter(AutoTest): self.context_pop() self.reboot_sitl() - def test_copter_gps_zero(self): + def PositionWhenGPSIsZero(self): + '''Ensure position doesn't zero when GPS lost''' # https://github.com/ArduPilot/ardupilot/issues/14236 self.progress("arm the vehicle and takeoff in Guided") self.takeoff(20, mode='GUIDED') @@ -7909,7 +7963,8 @@ class AutoTestCopter(AutoTest): self.wait_disarmed() self.reboot_sitl() - def test_SMART_RTL(self): + def SMART_RTL(self): + '''Check SMART_RTL''' self.context_push() ex = None try: @@ -7987,7 +8042,7 @@ class AutoTestCopter(AutoTest): return self.get_ground_effect_duration_from_current_onboard_log(12, ignore_multi=ignore_multi) def ThrowDoubleDrop(self): - # test boomerang mode: + '''Test a more complicated drop-mode scenario''' self.progress("Getting a lift to altitude") self.set_parameters({ "SIM_SHOVE_Z": -11, @@ -8041,6 +8096,7 @@ class AutoTestCopter(AutoTest): self.wait_disarmed(timeout=240) def GroundEffectCompensation_takeOffExpected(self): + '''Test EKF's handling of takeoff-expected''' self.change_mode('ALT_HOLD') self.set_parameter("LOG_FILE_DSRMROT", 1) self.progress("Making sure we'll have a short log to look at") @@ -8144,10 +8200,12 @@ class AutoTestCopter(AutoTest): pass def MAV_CMD_CONDITION_YAW(self): + '''Test response to MAV_CMD_CONDITION_YAW''' self.MAV_CMD_CONDITION_YAW_absolute() self.MAV_CMD_CONDITION_YAW_relative() def GroundEffectCompensation_touchDownExpected(self): + '''Test EKF's handling of touchdown-expected''' self.zero_throttle() self.change_mode('ALT_HOLD') self.set_parameter("LOG_FILE_DSRMROT", 1) @@ -8183,6 +8241,7 @@ class AutoTestCopter(AutoTest): self.upload_simple_relhome_mission(items) def RefindGPS(self): + '''Refind the GPS and attempt to RTL rather than continue to land''' # https://github.com/ArduPilot/ardupilot/issues/14236 self.progress("arm the vehicle and takeoff in Guided") self.takeoff(20, mode='GUIDED') @@ -8205,6 +8264,7 @@ class AutoTestCopter(AutoTest): self.do_RTL() def GPSForYaw(self): + '''Moving baseline GPS yaw''' self.context_push() self.load_default_params_file("copter-gps-for-yaw.parm") self.reboot_sitl() @@ -8229,6 +8289,7 @@ class AutoTestCopter(AutoTest): raise ex def AP_Avoidance(self): + '''ADSB-based avoidance''' self.set_parameters({ "AVD_ENABLE": 1, "ADSB_TYPE": 1, # mavlink @@ -8269,6 +8330,7 @@ class AutoTestCopter(AutoTest): self.context_pop() def PAUSE_CONTINUE(self): + '''Test MAV_CMD_DO_PAUSE_CONTINUE in AUTO mode''' self.load_mission(filename="copter_mission.txt", strict=False) self.set_parameter(name="AUTO_OPTIONS", value=3) self.change_mode(mode="AUTO") @@ -8288,6 +8350,7 @@ class AutoTestCopter(AutoTest): self.wait_disarmed(timeout=500) def PAUSE_CONTINUE_GUIDED(self): + '''Test MAV_CMD_DO_PAUSE_CONTINUE in GUIDED mode''' self.start_subtest("Started test for Pause/Continue in GUIDED mode with LOCATION!") self.change_mode(mode="GUIDED") self.wait_ready_to_arm() @@ -8438,6 +8501,7 @@ class AutoTestCopter(AutoTest): self.do_RTL(timeout=120) def DO_CHANGE_SPEED(self): + '''Change speed during misison using waypoint items''' self.load_mission("mission.txt", strict=False) self.set_parameters({ @@ -8675,6 +8739,7 @@ class AutoTestCopter(AutoTest): self.fettec_assert_good_mask(good_mask) def FETtecESC(self): + '''Test FETtecESC''' self.set_parameters({ "SERIAL5_PROTOCOL": 38, "SERVO_FTW_MASK": 0b11101000, @@ -8695,6 +8760,7 @@ class AutoTestCopter(AutoTest): self.FETtecESC_flight() def PerfInfo(self): + '''Test Scheduler PerfInfo output''' self.set_parameter('SCHED_OPTIONS', 1) # enable gathering # sometimes we need to trigger collection.... content = self.fetch_file_via_ftp("@SYS/tasks.txt") @@ -8711,6 +8777,7 @@ class AutoTestCopter(AutoTest): raise NotAchievedException("Expected EFI last not (%s)" % lines[-2]) def RTL_TO_RALLY(self, target_system=1, target_component=1): + '''Check RTL to rally point''' self.wait_ready_to_arm() rally_loc = self.home_relative_loc_ne(50, -25) rally_alt = 37 @@ -8753,6 +8820,7 @@ class AutoTestCopter(AutoTest): self.assert_at_home() def NoRCOnBootPreArmFailure(self): + '''Ensure we can't arm with no RC on boot if THR_FS_VALUE set''' self.context_push() for rc_failure_mode in 1, 2: self.set_parameters({ @@ -8768,398 +8836,123 @@ class AutoTestCopter(AutoTest): '''return list of all tests''' ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py ret.extend([ - ("NavDelayTakeoffAbsTime", - "Fly Nav Delay (takeoff)", - self.fly_nav_takeoff_delay_abstime), # 19s - - ("NavDelayAbsTime", - "Fly Nav Delay (AbsTime)", - self.fly_nav_delay_abstime), # 20s - - ("NavDelay", - "Fly Nav Delay", - self.fly_nav_delay), # 19s - - ("GuidedSubModeChange", - "Test submode change", - self.GuidedSubModeChange), - - ("MAV_CMD_CONDITION_YAW", - "Test response to MAV_CMD_CONDITION_YAW", - self.MAV_CMD_CONDITION_YAW), - - ("LoiterToAlt", - "Loiter-To-Alt", - self.fly_loiter_to_alt), # 25s - - ("PayLoadPlaceMission", - "Payload Place Mission", - self.PayLoadPlaceMission), # 44s - - ("PrecisionLoiterCompanion", - "Precision Loiter (Companion)", - self.PrecisionLoiterCompanion), # 29s - - ("Landing", - "Test landing", - self.Landing), - - ("PrecisionLandingSITL", - "Precision Landing drivers (SITL)", - self.fly_precision_landing_drivers), # 29s - - ("SetModesViaModeSwitch", - "Set modes via modeswitch", - self.test_setting_modes_via_modeswitch), - - ("SetModesViaAuxSwitch", - "Set modes via auxswitch", - self.test_setting_modes_via_auxswitch), - - ("AuxSwitchOptions", - "Test random aux mode options", - self.test_aux_switch_options), - - ("AuxFunctionsInMission", - "Test use of auxilliary functions in missions", - self.test_aux_functions_in_mission), - - ("AutoTune", - "Fly AUTOTUNE mode", - self.fly_autotune), # 73s - - ("NoRCOnBootPreArmFailure", - "Ensure we can't arm with no RC on boot if THR_FS_VALUE set", - self.NoRCOnBootPreArmFailure), + self.NavDelayTakeoffAbsTime, + self.NavDelayAbsTime, + self.NavDelay, + self.GuidedSubModeChange, + self.MAV_CMD_CONDITION_YAW, + self.LoiterToAlt, + self.PayLoadPlaceMission, + self.PrecisionLoiterCompanion, + self.Landing, + self.PrecisionLanding, + self.SetModesViaModeSwitch, + self.SetModesViaAuxSwitch, + self.AuxSwitchOptions, + self.AuxFunctionsInMission, + self.AutoTune, + self.NoRCOnBootPreArmFailure, ]) return ret def tests1b(self): '''return list of all tests''' ret = ([ - ("ThrowMode", "Fly Throw Mode", self.fly_throw_mode), - - ("BrakeMode", "Fly Brake Mode", self.fly_brake_mode), - - ("RecordThenPlayMission", - "Use switches to toggle in mission, then fly it", - self.fly_square), # 27s - - ("ThrottleFailsafe", - "Test Throttle Failsafe", - self.fly_throttle_failsafe), # 173s - - ("GCSFailsafe", - "Test GCS Failsafe", - self.fly_gcs_failsafe), # 239s - - ("CustomController", - "Test Custom Controller", - self.test_custom_controller), - - # this group has the smallest runtime right now at around - # 5mins, so add more tests here, till its around - # 9-10mins, then make a new group + self.ThrowMode, + self.BrakeMode, + self.RecordThenPlayMission, + self.ThrottleFailsafe, + self.GCSFailsafe, + self.CustomController, ]) return ret def tests1c(self): '''return list of all tests''' ret = ([ - ("BatteryFailsafe", - "Fly Battery Failsafe", - self.fly_battery_failsafe), # 164s - - ("VibrationFailsafe", - "Test Vibration Failsafe", - self.test_vibration_failsafe), - - ("EK3AccelBias", - "Test EK3 Accel Bias data", - self.EK3AccelBias), - - ("StabilityPatch", - "Fly stability patch", - lambda: self.fly_stability_patch(30)), # 17s - - ("OBSTACLE_DISTANCE_3D", - "Check round-trip behaviour of distance sensors", - self.OBSTACLE_DISTANCE_3D), # ??s - - ("AC_Avoidance_Proximity", - "Test proximity avoidance slide behaviour", - self.fly_proximity_avoidance_test), # 41s - - ("AC_Avoidance_Fence", - "Test fence avoidance slide behaviour", - self.fly_fence_avoidance_test), - - ("AC_Avoidance_Beacon", - "Test beacon avoidance slide behaviour", - self.fly_beacon_avoidance_test), # 28s - - ("BaroWindCorrection", - "Test wind estimation and baro position error compensation", - self.fly_wind_baro_compensation), - - ("SetpointGlobalPos", - "Test setpoint global position", - self.test_set_position_global_int), - - ("ThrowDoubleDrop", - "Test a more complicated drop-mode scenario", - self.ThrowDoubleDrop), - - ("SetpointGlobalVel", - "Test setpoint global velocity", - self.test_set_velocity_global_int), - - ("SplineTerrain", - "Test Splines and Terrain", - self.test_terrain_spline_mission), - - ("TakeoffCheck", - "Test takeoff check", - self.test_takeoff_check), + self.BatteryFailsafe, + self.VibrationFailsafe, + self.EK3AccelBias, + self.StabilityPatch, + self.OBSTACLE_DISTANCE_3D, + self.AC_Avoidance_Proximity, + self.AC_Avoidance_Fence, + self.AC_Avoidance_Beacon, + self.BaroWindCorrection, + self.SetpointGlobalPos, + self.ThrowDoubleDrop, + self.SetpointGlobalVel, + self.SplineTerrain, + self.TakeoffCheck, ]) return ret def tests1d(self): '''return list of all tests''' ret = ([ - ("HorizontalFence", - "Test horizontal fence", - self.fly_fence_test), # 20s - - ("HorizontalAvoidFence", - "Test horizontal Avoidance fence", - self.fly_fence_avoid_test), - - ("MaxAltFence", - "Test Max Alt Fence", - self.fly_alt_max_fence_test), # 26s - - ("MinAltFence", - "Test Min Alt Fence", - self.fly_alt_min_fence_test), # 26s - - ("FenceFloorEnabledLanding", - "Test Landing with Fence floor enabled", - self.fly_fence_floor_enabled_landing), - - ("AutoTuneSwitch", - "Fly AUTOTUNE on a switch", - self.fly_autotune_switch), # 105s - - ("GPSGlitchLoiter", - "GPS Glitch Loiter Test", - self.fly_gps_glitch_loiter_test), # 30s - - ("GPSGlitchLoiter2", - "GPS Glitch Loiter Test2", - self.fly_gps_glitch_loiter_test2), # 30s - - ("GPSGlitchAuto", - "GPS Glitch Auto Test", - self.fly_gps_glitch_auto_test), - - ("ModeAltHold", - "Test AltHold Mode", - self.test_mode_ALT_HOLD), - - ("ModeLoiter", - "Test Loiter Mode", - self.loiter), - - ("SimpleMode", - "Fly in SIMPLE mode", - self.fly_simple), - - ("SuperSimpleCircle", - "Fly a circle in SUPER SIMPLE mode", - self.fly_super_simple), # 38s - - ("ModeCircle", - "Fly CIRCLE mode", - self.fly_circle), # 27s - - ("MagFail", - "Test magnetometer failure", - self.test_mag_fail), - - ("OpticalFlow", - "Test Optical Flow", - self.optical_flow), - - ("OpticalFlowLimits", - "Fly Optical Flow limits", - self.fly_optical_flow_limits), # 27s - - ("OpticalFlowCalibration", - "Fly Optical Flow calibration", - self.fly_optical_flow_calibration), - - ("MotorFail", - "Fly motor failure test", - self.fly_motor_fail), - - ("Flip", - "Fly Flip Mode", - self.fly_flip), - - ("CopterMission", - "Fly copter mission", - self.fly_auto_test), # 37s - - ("TakeoffAlt", - "Test Takeoff command altitude", - self.test_takeoff_alt), # 12s - - ("SplineLastWaypoint", - "Test Spline as last waypoint", - self.test_spline_last_waypoint), - - ("Gripper", - "Test gripper", - self.test_gripper), # 28s - - ("TestGripperMission", - "Test Gripper mission items", - self.test_gripper_mission), - - ("VisionPosition", - "Fly Vision Position", - self.fly_vision_position), # 24s - - ("ATTITUDE_FAST", - "Ensure ATTITUTDE_FAST logging works", - self.ATTITUDE_FAST), - - ("BaseLoggingRates", - "Ensure base logging rates as expected", - self.BaseLoggingRates), - - ("BodyFrameOdom", - "Fly Body Frame Odometry Code", - self.fly_body_frame_odom), # 24s - - ("GPSViconSwitching", - "Fly GPS and Vicon Switching", - self.fly_gps_vicon_switching), + self.HorizontalFence, + self.HorizontalAvoidFence, + self.MaxAltFence, + self.MinAltFence, + self.FenceFloorEnabledLanding, + self.AutoTuneSwitch, + self.GPSGlitchLoiter, + self.GPSGlitchLoiter2, + self.GPSGlitchAuto, + self.ModeAltHold, + self.ModeLoiter, + self.SimpleMode, + self.SuperSimpleCircle, + self.ModeCircle, + self.MagFail, + self.OpticalFlow, + self.OpticalFlowLimits, + self.OpticalFlowCalibration, + self.MotorFail, + self.ModeFlip, + self.CopterMission, + self.TakeoffAlt, + self.SplineLastWaypoint, + self.Gripper, + self.TestGripperMission, + self.VisionPosition, + self.ATTITUDE_FAST, + self.BaseLoggingRates, + self.BodyFrameOdom, + self.GPSViconSwitching, ]) return ret def tests1e(self): '''return list of all tests''' ret = ([ - ("BeaconPosition", - "Fly Beacon Position", - self.fly_beacon_position), # 56s - - ("RTLSpeed", - "Fly RTL Speed", - self.fly_rtl_speed), - - ("Mount", - "Test Camera/Antenna Mount", - self.test_mount), # 74s - - ("MountYawVehicleForMountROI", - "Test Camera/Antenna Mount vehicle yawing for ROI", - self.MountYawVehicleForMountROI), - - ("Button", - "Test Buttons", - self.test_button), - - ("ShipTakeoff", - "Fly Simulated Ship Takeoff", - self.fly_ship_takeoff), - - ("RangeFinder", - "Test RangeFinder Basic Functionality", - self.test_rangefinder), # 23s - - ("BaroDrivers", - "Test Baro Drivers", - self.BaroDrivers), - - ("SurfaceTracking", - "Test Surface Tracking", - self.test_surface_tracking), # 45s - - ("Parachute", - "Test Parachute Functionality", - self.test_parachute), - - ("ParameterChecks", - "Test Arming Parameter Checks", - self.test_parameter_checks), - - ("ManualThrottleModeChange", - "Check manual throttle mode changes denied on high throttle", - self.fly_manual_throttle_mode_change), - - ("MANUAL_CONTROL", - "Test mavlink MANUAL_CONTROL", - self.test_manual_control), - - ("ZigZag", - "Fly ZigZag Mode", - self.fly_zigzag_mode), # 58s - - ("PosHoldTakeOff", - "Fly POSHOLD takeoff", - self.fly_poshold_takeoff), - - ("FOLLOW", - "Fly follow mode", - self.fly_follow_mode), # 80s - - ("RangeFinderDrivers", - "Test rangefinder drivers", - self.fly_rangefinder_drivers), # 62s - - ("RangeFinderDriversMaxAlt", - "Test rangefinder drivers - test max alt", - self.fly_rangefinder_drivers_maxalt), # 25s - - ("MaxBotixI2CXL", - "Test maxbotix rangefinder drivers", - self.fly_rangefinder_driver_maxbotix), # 62s - - ("MAVProximity", - "Test MAVLink proximity driver", - self.fly_proximity_mavlink_distance_sensor, - ), - - ("ParameterValidation", - "Test parameters are checked for validity", - self.test_parameter_validation), - - ("AltTypes", - "Test Different Altitude Types", - self.test_altitude_types), - - ("PAUSE_CONTINUE", - "Test MAV_CMD_DO_PAUSE_CONTINUE in AUTO mode", - self.PAUSE_CONTINUE), - - ("PAUSE_CONTINUE_GUIDED", - "Test MAV_CMD_DO_PAUSE_CONTINUE in GUIDED mode", - self.PAUSE_CONTINUE_GUIDED), - - ("RichenPower", - "Test RichenPower generator", - self.test_richenpower), - - ("IE24", - "Test IntelligentEnergy 2.4kWh generator", - self.test_ie24), - - ("LogUpload", - "Log upload", - self.log_upload), + self.BeaconPosition, + self.RTLSpeed, + self.Mount, + self.MountYawVehicleForMountROI, + self.Button, + self.ShipTakeoff, + self.RangeFinder, + self.BaroDrivers, + self.SurfaceTracking, + self.Parachute, + self.ParameterChecks, + self.ManualThrottleModeChange, + self.MANUAL_CONTROL, + self.ModeZigZag, + self.PosHoldTakeOff, + self.ModeFollow, + self.RangeFinderDrivers, + self.RangeFinderDriversMaxAlt, + self.MaxBotixI2CXL, + self.MAVProximity, + self.ParameterValidation, + self.AltTypes, + self.PAUSE_CONTINUE, + self.PAUSE_CONTINUE_GUIDED, + self.RichenPower, + self.IE24, + self.LogUpload, ]) return ret @@ -9168,195 +8961,66 @@ class AutoTestCopter(AutoTest): ret = ([ # something about SITLCompassCalibration appears to fail # this one, so we put it first: - ("FixedYawCalibration", - "Test Fixed Yaw Calibration", # about 20 secs - self.test_fixed_yaw_calibration), + self.FixedYawCalibration, - # we run this single 8min-and-40s test on its own, apart from - # requiring FixedYawCalibration right before it because without it, it fails to calibrate - ("SITLCompassCalibration", # this autotest appears to interfere with FixedYawCalibration, no idea why. - "Test SITL onboard compass calibration", - self.test_mag_calibration), + # we run this single 8min-and-40s test on its own, apart + # from requiring FixedYawCalibration right before it + # because without it, it fails to calibrate this + # autotest appears to interfere with + # FixedYawCalibration, no idea why. + self.SITLCompassCalibration, ]) return ret def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ - Test("MotorVibration", - "Fly motor vibration test", - self.fly_motor_vibration), - - Test("DynamicNotches", - "Fly Dynamic Notches", - self.fly_dynamic_notches, - attempts=8), - - Test("PositionWhenGPSIsZero", - "Ensure position doesn't zero when GPS lost", - self.test_copter_gps_zero), - - Test("DynamicRpmNotches", - "Fly Dynamic Notches driven by ESC Telemetry", - self.fly_esc_telemetry_notches, - attempts=8), - - Test("RefindGPS", - "Refind the GPS and attempt to RTL rather than continue to land", - self.RefindGPS), - - Test("GyroFFT", - "Fly Gyro FFT", - self.fly_gyro_fft, - attempts=8), - - Test("GyroFFTHarmonic", - "Fly Gyro FFT Harmonic Matching", - self.fly_gyro_fft_harmonic, - attempts=8), - - Test("GyroFFTAverage", - "Fly Gyro FFT Averaging", - self.fly_gyro_fft_average, - attempts=1), - - Test("GyroFFTContinuousAveraging", - "Fly Gyro FFT Continuous averaging", - self.fly_gyro_fft_continuous_averaging, - attempts=8), - - Test("CompassReordering", - "Test Compass reordering when priorities are changed", - self.test_mag_reordering), # 40sec? - - Test("CRSF", - "Test RC CRSF", - self.test_crsf), # 20secs ish - - Test("MotorTest", - "Run Motor Tests", - self.test_motortest), # 20secs ish - - Test("AltEstimation", - "Test that Alt Estimation is mandatory for ALT_HOLD", - self.test_alt_estimate_prearm), # 20secs ish - - Test("EKFSource", - "Check EKF Source Prearms work", - self.test_ekf_source), - - Test("GSF", - "Check GSF", - self.test_gsf), - - Test("AP_Avoidance", - "ADSB-based avoidance", - self.AP_Avoidance), - - Test("SMART_RTL", - "Check SMART_RTL", - self.test_SMART_RTL), - - Test("RTL_TO_RALLY", - "Check RTL to rally point", - self.RTL_TO_RALLY), - - Test("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), - - Test("GPSBlending", - "Test GPS Blending", - self.test_gps_blending), - - Test("DataFlash", - "Test DataFlash Block backend", - self.test_dataflash_sitl), - - Test("DataFlashErase", - "Test DataFlash Block backend erase", - self.test_dataflash_erase, - attempts=8), - - Test("Callisto", - "Test Callisto", - self.test_callisto), - - Test("PerfInfo", - "Test Scheduler PerfInfo output", - self.PerfInfo), - - Test("Replay", - "Test Replay", - self.test_replay), - - Test("FETtecESC", - "Test FETtecESC", - self.FETtecESC), - - Test("ProximitySensors", - "Test Proximity Sensors", - self.ProximitySensors), - - Test("GroundEffectCompensation_touchDownExpected", - "Test EKF's handling of touchdown-expected", - self.GroundEffectCompensation_touchDownExpected), - - Test("GroundEffectCompensation_takeOffExpected", - "Test EKF's handling of takeoff-expected", - self.GroundEffectCompensation_takeOffExpected), - - Test("DO_CHANGE_SPEED", - "Change speed during misison using waypoint items", - self.DO_CHANGE_SPEED), - - Test("AUTO_LAND_TO_BRAKE", - "Change to LAND while descending in AUTO land phase", - self.AUTO_LAND_TO_BRAKE), - - Test("WPNAV_SPEED", - "Change speed during misison", - self.WPNAV_SPEED), - - Test("WPNAV_SPEED_UP", - "Change speed (up) during misison", - self.WPNAV_SPEED_UP), - - Test("WPNAV_SPEED_DN", - "Change speed (down) during misison", - self.WPNAV_SPEED_DN), - - Test("SensorErrorFlags", - "Test we get ERR messages when sensors have issues", - self.SensorErrorFlags), - - Test("GPSForYaw", - "Moving baseline GPS yaw", - self.GPSForYaw), - - ("DefaultIntervalsFromFiles", - "Test setting default mavlink message intervals from files", - self.DefaultIntervalsFromFiles), - - Test("GPSTypes", - "Test simulated GPS types", - self.GPSTypes), - - Test("MultipleGPS", - "Test multi-GPS behaviour", - self.MultipleGPS), - - Test("LogUpload", - "Log upload", - self.log_upload), + self.MotorVibration, + Test(self.DynamicNotches, attempts=8), + self.PositionWhenGPSIsZero, + Test(self.DynamicRpmNotches, attempts=8), + self.RefindGPS, + Test(self.GyroFFT, attempts=8), + Test(self.GyroFFTHarmonic, attempts=8), + self.GyroFFTAverage, + Test(self.GyroFFTContinuousAveraging, attempts=8), + self.CompassReordering, + self.CRSF, + self.MotorTest, + self.AltEstimation, + self.EKFSource, + self.GSF, + self.AP_Avoidance, + self.SMART_RTL, + self.RTL_TO_RALLY, + self.FlyEachFrame, + self.GPSBlending, + self.DataFlash, + Test(self.DataFlashErase, attempts=8), + self.Callisto, + self.PerfInfo, + self.Replay, + self.FETtecESC, + self.ProximitySensors, + self.GroundEffectCompensation_touchDownExpected, + self.GroundEffectCompensation_takeOffExpected, + self.DO_CHANGE_SPEED, + self.AUTO_LAND_TO_BRAKE, + self.WPNAV_SPEED, + self.WPNAV_SPEED_UP, + self.WPNAV_SPEED_DN, + self.SensorErrorFlags, + self.GPSForYaw, + self.DefaultIntervalsFromFiles, + self.GPSTypes, + self.MultipleGPS, + self.LogUpload, ]) return ret def testcan(self): ret = ([ - ("CANGPSCopterMission", - "Fly copter mission", - self.fly_auto_test_using_can_gps), + self.CANGPSCopterMission, ]) return ret diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 2fc589e533..7218fa57ca 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -550,7 +550,8 @@ class AutoTestPlane(AutoTest): self.context_pop() self.progress("Mission OK") - def fly_do_reposition(self): + def DO_REPOSITION(self): + '''Test mavlink DO_REPOSITION command''' self.progress("Takeoff") self.takeoff(alt=50) self.set_rc(3, 1500) @@ -575,7 +576,8 @@ class AutoTestPlane(AutoTest): self.fly_home_land_and_disarm() - def fly_deepstall(self): + def DeepStall(self): + '''Test DeepStall Landing''' # self.fly_deepstall_absolute() self.fly_deepstall_relative() @@ -648,6 +650,7 @@ class AutoTestPlane(AutoTest): self.fly_home_land_and_disarm(timeout=240) def SmartBattery(self): + '''Test smart battery logging etc''' self.set_parameters({ "BATT_MONITOR": 16, # Maxell battery monitor }) @@ -674,7 +677,7 @@ class AutoTestPlane(AutoTest): raise NotAchievedException("Expected BCL2 message") def DO_CHANGE_SPEED(self): - '''test DO_CHANGE_SPEED both as a mavlink command and as a mission item''' + '''Test DO_CHANGE_SPEED command/item''' # the following lines ensure we revert these parameter values # - DO_CHANGE_AIRSPEED is a permanent vehicle change! self.set_parameters({ @@ -814,7 +817,7 @@ class AutoTestPlane(AutoTest): # this is probably too noisy anyway? self.wait_disarmed(timeout=timeout) - def fly_flaps(self): + def TestFlaps(self): """Test flaps functionality.""" filename = "flaps.txt" self.context_push() @@ -907,8 +910,8 @@ class AutoTestPlane(AutoTest): self.disarm_vehicle() raise ex - def test_rc_relay(self): - '''test toggling channel 12 toggles relay''' + def TestRCRelay(self): + '''Test Relay RC Channel Option''' self.set_parameter("RC12_OPTION", 28) # Relay On/Off self.set_rc(12, 1000) self.reboot_sitl() # needed for RC12_OPTION to take effect @@ -934,8 +937,8 @@ class AutoTestPlane(AutoTest): if off: raise NotAchievedException("SIM_PIN_MASK doesn't reflect OFF") - def test_rc_option_camera_trigger(self): - '''test toggling channel 12 takes picture''' + def TestRCCamera(self): + '''Test RC Option - Camera Trigger''' self.set_parameter("RC12_OPTION", 9) # CameraTrigger self.reboot_sitl() # needed for RC12_OPTION to take effect @@ -970,6 +973,7 @@ class AutoTestPlane(AutoTest): self.fly_home_land_and_disarm() def ThrottleFailsafe(self): + '''Fly throttle failsafe''' self.change_mode('MANUAL') m = self.mav.recv_match(type='SYS_STATUS', blocking=True) receiver_bit = mavutil.mavlink.MAV_SYS_STATUS_SENSOR_RC_RECEIVER @@ -1113,7 +1117,8 @@ class AutoTestPlane(AutoTest): self.context_pop() self.reboot_sitl() - def test_throttle_failsafe_fence(self): + def ThrottleFailsafeFence(self): + '''Fly fence survives throttle failsafe''' fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.progress("Checking fence is not present before being configured") @@ -1161,7 +1166,8 @@ class AutoTestPlane(AutoTest): raise NotAchievedException("Fence not enabled after RC fail") self.do_fence_disable() # Ensure the fence is disabled after test - def test_gripper_mission(self): + def TestGripperMission(self): + '''Test Gripper mission items''' self.context_push() ex = None try: @@ -1241,7 +1247,8 @@ class AutoTestPlane(AutoTest): on_radius_start_heading = None circle_time_start = 0 - def test_fence_static(self): + def FenceStatic(self): + '''Test Basic Fence Functionality''' ex = None try: self.progress("Checking for bizarre healthy-when-not-present-or-enabled") @@ -1416,14 +1423,16 @@ class AutoTestPlane(AutoTest): if ex is not None: raise ex - def test_fence_rtl(self): + def FenceRTL(self): + '''Test Fence RTL''' self.progress("Testing FENCE_ACTION_RTL no rally point") # have to disable the fence once we've breached or we breach # it as part of the loiter-at-home! self.test_fence_breach_circle_at(self.home_position_as_mav_location(), disable_on_breach=True) - def test_fence_rtl_rally(self): + def FenceRTLRally(self): + '''Test Fence RTL Rally''' ex = None target_system = 1 target_component = 1 @@ -1455,7 +1464,7 @@ class AutoTestPlane(AutoTest): if ex is not None: raise ex - def test_fence_ret_rally(self): + def FenceRetRally(self): """ Tests the FENCE_RET_RALLY flag, either returning to fence return point, or rally point """ target_system = 1 @@ -1542,7 +1551,8 @@ class AutoTestPlane(AutoTest): self.do_fence_disable() # Disable fence so we can land self.fly_home_land_and_disarm() # Pack it up, we're going home. - def test_parachute(self): + def Parachute(self): + '''Test Parachute''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -1561,7 +1571,8 @@ class AutoTestPlane(AutoTest): self.disarm_vehicle(force=True) self.reboot_sitl() - def test_parachute_sinkrate(self): + def ParachuteSinkRate(self): + '''Test Parachute (SinkRate triggering)''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -1672,8 +1683,8 @@ class AutoTestPlane(AutoTest): self.check_attitudes_match(1, 2) - def test_main_flight(self): - + def MainFlight(self): + '''Lots of things in one flight''' self.change_mode('MANUAL') self.progress("Asserting we do support transfer of fence via mission item protocol") @@ -1712,7 +1723,8 @@ class AutoTestPlane(AutoTest): self.run_subtest("Mission test", lambda: self.fly_mission("ap1.txt", strict=False)) - def airspeed_autocal(self): + def AIRSPEED_AUTOCAL(self): + '''Test AIRSPEED_AUTOCAL''' self.progress("Ensure no AIRSPEED_AUTOCAL on ground") self.set_parameters({ "ARSPD_AUTOCAL": 1, @@ -1815,13 +1827,16 @@ class AutoTestPlane(AutoTest): finally: self.remove_message_hook(validate_global_position_int_against_simstate) - def deadreckoning(self): + def Deadreckoning(self): + '''Test deadreckoning support''' self.deadreckoning_main() - def deadreckoning_no_airspeed_sensor(self): + def DeadreckoningNoAirSpeed(self): + '''Test deadreckoning support with no airspeed sensor''' self.deadreckoning_main(disable_airspeed_sensor=True) - def climb_before_turn(self): + def ClimbBeforeTurn(self): + '''Test climb-before-turn''' self.wait_ready_to_arm() self.set_parameters({ "FLIGHT_OPTIONS": 0, @@ -1879,7 +1894,8 @@ class AutoTestPlane(AutoTest): self.fly_home_land_and_disarm(timeout=240) - def rtl_climb_min(self): + def RTL_CLIMB_MIN(self): + '''Test RTL_CLIMB_MIN''' self.wait_ready_to_arm() rtl_climb_min = 100 self.set_parameter("RTL_CLIMB_MIN", rtl_climb_min) @@ -1925,7 +1941,8 @@ class AutoTestPlane(AutoTest): def sample_enable_parameter(self): return "Q_ENABLE" - def test_rangefinder(self): + def RangeFinder(self): + '''Test RangeFinder Basic Functionality''' ex = None self.context_push() self.progress("Making sure we don't ordinarily get RANGEFINDER") @@ -1989,11 +2006,13 @@ class AutoTestPlane(AutoTest): def default_mode(self): return "MANUAL" - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.change_mode("FBWA") # we don't update PIDs in MANUAL - super(AutoTestPlane, self).test_pid_tuning() + super(AutoTestPlane, self).PIDTuning() - def test_setting_modes_via_auxswitches(self): + def AuxModeSwitch(self): + '''Set modes via auxswitches''' self.set_parameter("FLTMODE1", 1) # circle self.set_rc(8, 950) self.wait_mode("CIRCLE") @@ -2039,8 +2058,7 @@ class AutoTestPlane(AutoTest): last_collision = now def SimADSB(self): - '''trivial tests to ensure simulated ADSB sensor continues to -function''' + '''Tests to ensure simulated ADSB sensor continues to function''' self.set_parameters({ "SIM_ADSB_COUNT": 1, "ADSB_TYPE": 1, @@ -2049,6 +2067,7 @@ function''' self.assert_receive_message('ADSB_VEHICLE', timeout=30) def ADSB(self): + '''Test ADSB''' self.ADSB_f_action_rtl() self.ADSB_r_action_resume_or_loiter() @@ -2153,7 +2172,8 @@ function''' if ex is not None: raise ex - def fly_do_guided_request(self, target_system=1, target_component=1): + def GuidedRequest(self, target_system=1, target_component=1): + '''Test handling of MISSION_ITEM in guided mode''' self.progress("Takeoff") self.takeoff(alt=50) self.set_rc(3, 1500) @@ -2239,6 +2259,7 @@ function''' self.fly_home_land_and_disarm() def LOITER(self): + '''Test Loiter mode''' # first test old loiter behavour self.set_parameter("FLIGHT_OPTIONS", 0) self.takeoff(alt=200) @@ -2306,11 +2327,13 @@ function''' '''In lockup Plane should copy RC inputs to RC outputs''' self.plane_CPUFailsafe() - def test_large_missions(self): + def LargeMissions(self): + '''Test Manipulation of Large missions''' self.load_mission("Kingaroy-vlarge.txt", strict=False) self.load_mission("Kingaroy-vlarge2.txt", strict=False) - def fly_soaring(self): + def Soaring(self): + '''Test Soaring feature''' model = "plane-soaring" @@ -2421,7 +2444,8 @@ function''' self.progress("Mission OK") - def fly_soaring_speed_to_fly(self): + def SpeedToFly(self): + '''Test soaring speed-to-fly''' model = "plane-soaring" @@ -2553,7 +2577,8 @@ function''' self.disarm_vehicle(force=True) self.reboot_sitl() - def test_airspeed_drivers(self): + def AirspeedDrivers(self): + '''Test AirSpeed drivers''' airspeed_sensors = [ ("MS5525", 3, 1), ("DLVR", 7, 2), @@ -2608,7 +2633,7 @@ function''' self.reboot_sitl() def TerrainMission(self): - + '''Test terrain following in mission''' self.install_terrain_handlers_context() num_wp = self.load_mission("ap-terrain.txt") @@ -2679,6 +2704,7 @@ function''' (expected_terrain_height, report.terrain_height)) def TerrainLoiter(self): + '''Test terrain following in loiter''' self.context_push() self.set_parameters({ "TERRAIN_FOLLOW": 1, # enable terrain following in loiter @@ -2727,10 +2753,12 @@ function''' self.arm_vehicle() self.fly_mission(mission) - def test_vectornav(self): + def VectorNavEAHRS(self): + '''Test VectorNav EAHRS support''' self.fly_external_AHRS("VectorNav", 1, "ap1.txt") - def test_lord(self): + def LordEAHRS(self): + '''Test LORD Microstrain EAHRS support''' self.fly_external_AHRS("LORD", 2, "ap1.txt") def get_accelvec(self, m): @@ -2739,7 +2767,8 @@ function''' def get_gyrovec(self, m): return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1) - def test_imu_tempcal(self): + def IMUTempCal(self): + '''Test IMU temperature calibration''' self.progress("Setting up SITL temperature profile") self.set_parameters({ "SIM_IMUT1_ENABLE" : 1, @@ -2908,7 +2937,8 @@ function''' # parameters). So wipe the vehicle's eeprom: self.reset_SITL_commandline() - def ekf_lane_switch(self): + def EKFlaneswitch(self): + '''Test EKF3 Affinity and Lane Switching''' self.context_push() ex = None @@ -3106,7 +3136,8 @@ function''' if ex is not None: raise ex - def test_fence_alt_ceil_floor(self): + def FenceAltCeilFloor(self): + '''Tests the fence ceiling and floor''' fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.set_parameters({ "FENCE_TYPE": 9, # Set fence type to max and min alt @@ -3151,7 +3182,8 @@ function''' self.fly_home_land_and_disarm(timeout=150) - def test_fence_breached_change_mode(self): + def FenceBreachedChangeMode(self): + '''Tests manual mode change after fence breach, as set with FENCE_OPTIONS''' """ Attempts to change mode while a fence is breached. mode should change should fail if fence option bit is set""" self.set_parameters({ @@ -3210,7 +3242,8 @@ function''' self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_breach_no_return_point(self): + def FenceNoFenceReturnPoint(self): + '''Tests calculated return point during fence breach when no fence return point present''' """ Attempts to change mode while a fence is breached. This should revert to the mode specified by the fence action. """ want_radius = 100 # Fence Return Radius @@ -3285,7 +3318,8 @@ function''' self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_breach_no_return_point_no_inclusion(self): + def FenceNoFenceReturnPointInclusion(self): + '''Tests using home as fence return point when none is present, and no inclusion fence is uploaded''' """ Test result when a breach occurs and No fence return point is present and no inclusion fence is present and exclusion fence is present """ want_radius = 100 # Fence Return Radius @@ -3333,7 +3367,8 @@ function''' self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_disable_under_breach_action(self): + def FenceDisableUnderAction(self): + '''Tests Disabling fence while undergoing action caused by breach''' """ Fence breach will cause the vehicle to enter guided mode. Upon breach clear, check the vehicle is in the expected mode""" self.set_parameters({ @@ -3374,7 +3409,8 @@ function''' want_result=want_result ) - def fly_aux_function(self): + def MAV_DO_AUX_FUNCTION(self): + '''Test triggering Auxiliary Functions via mavlink''' self.context_collect('STATUSTEXT') self.run_auxfunc(64, 2) # 64 == reverse throttle self.wait_statustext("RevThrottle: ENABLE", check_context=True) @@ -3396,7 +3432,8 @@ function''' want_result=mavutil.mavlink.MAV_RESULT_DENIED ) - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -3444,6 +3481,7 @@ function''' self.wait_disarmed() def RCDisableAirspeedUse(self): + '''Test RC DisableAirspeedUse option''' self.set_parameter("RC9_OPTION", 106) self.delay_sim_time(5) self.set_rc(9, 1000) @@ -3466,6 +3504,7 @@ function''' True) def WatchdogHome(self): + '''Ensure home is restored after watchdog reset''' if self.gdb: # we end up signalling the wrong process. I think. # Probably need to have a "sitl_pid()" method to get the @@ -3519,6 +3558,7 @@ function''' raise ex def AUTOTUNE(self): + '''Test AutoTune mode''' self.takeoff(100) self.change_mode('AUTOTUNE') self.context_collect('STATUSTEXT') @@ -3569,8 +3609,8 @@ function''' self.change_mode('FBWA') self.fly_home_land_and_disarm(timeout=tdelta+240) - def fly_landing_baro_drift(self): - + def LandingDrift(self): + '''Circuit with baro drift''' self.customise_SITL_commandline([], wipe=True) self.set_analog_rangefinder_parameters() @@ -3607,6 +3647,7 @@ function''' self.wait_disarmed(timeout=180) def DCMFallback(self): + '''Really annoy the EKF and force fallback''' self.reboot_sitl() self.delay_sim_time(30) self.wait_ready_to_arm() @@ -3631,7 +3672,7 @@ function''' self.fly_home_land_and_disarm() def ForcedDCM(self): - + '''Switch to DCM mid-flight''' self.wait_ready_to_arm() self.arm_vehicle() @@ -3644,6 +3685,7 @@ function''' self.fly_home_land_and_disarm() def MegaSquirt(self): + '''Test MegaSquirt EFI''' self.assert_not_receiving_message('EFI_STATUS') self.set_parameters({ 'SIM_EFI_TYPE': 1, @@ -3661,7 +3703,8 @@ function''' if m.intake_manifold_temperature < 20: raise NotAchievedException("Bad intake manifold temperature") - def test_glide_slope_threshold(self): + def GlideSlopeThresh(self): + '''Test rebuild glide slope if above and climbing''' # Test that GLIDE_SLOPE_THRESHOLD correctly controls re-planning glide slope # in the scenario that aircraft is above planned slope and slope is positive (climbing). @@ -3866,6 +3909,7 @@ function''' self.fly_home_land_and_disarm(timeout=180) def MidAirDisarmDisallowed(self): + '''Ensure mid-air disarm is not possible''' self.takeoff(50) disarmed = False try: @@ -3885,289 +3929,82 @@ function''' '''return list of all tests''' ret = super(AutoTestPlane, self).tests() ret.extend([ - - ("AuxModeSwitch", - "Set modes via auxswitches", - self.test_setting_modes_via_auxswitches), - - ("TestRCCamera", - "Test RC Option - Camera Trigger", - self.test_rc_option_camera_trigger), - - ("TestRCRelay", "Test Relay RC Channel Option", self.test_rc_relay), - - ("ThrottleFailsafe", - "Fly throttle failsafe", - self.ThrottleFailsafe), - - ("NeedEKFToArm", - "Ensure we need EKF to be healthy to arm", - self.NeedEKFToArm), - - ("ThrottleFailsafeFence", - "Fly fence survives throttle failsafe", - self.test_throttle_failsafe_fence), - - ("TestFlaps", "Flaps", self.fly_flaps), - - ("DO_CHANGE_SPEED", - "Test DO_CHANGE_SPEED command/item", - self.DO_CHANGE_SPEED), - - ("DO_REPOSITION", - "Test mavlink DO_REPOSITION command", - self.fly_do_reposition), - - ("GuidedRequest", - "Test handling of MISSION_ITEM in guided mode", - self.fly_do_guided_request), - - ("MainFlight", - "Lots of things in one flight", - self.test_main_flight), - - ("TestGripperMission", - "Test Gripper mission items", - self.test_gripper_mission), - - ("Parachute", "Test Parachute", self.test_parachute), - - ("ParachuteSinkRate", "Test Parachute (SinkRate triggering)", self.test_parachute_sinkrate), - - ("AIRSPEED_AUTOCAL", "Test AIRSPEED_AUTOCAL", self.airspeed_autocal), - - ("RangeFinder", - "Test RangeFinder Basic Functionality", - self.test_rangefinder), - - ("FenceStatic", - "Test Basic Fence Functionality", - self.test_fence_static), - - ("FenceRTL", - "Test Fence RTL", - self.test_fence_rtl), - - ("FenceRTLRally", - "Test Fence RTL Rally", - self.test_fence_rtl_rally), - - ("FenceRetRally", - "Test Fence Ret_Rally", - self.test_fence_ret_rally), - - ("FenceAltCeilFloor", - "Tests the fence ceiling and floor", - self.test_fence_alt_ceil_floor), - - ("FenceBreachedChangeMode", - "Tests manual mode change after fence breach, as set with FENCE_OPTIONS", - self.test_fence_breached_change_mode), - - ("FenceNoFenceReturnPoint", - "Tests calculated return point during fence breach when no fence return point present", - self.test_fence_breach_no_return_point), - - ("FenceNoFenceReturnPointInclusion", - "Tests using home as fence return point when none is present, and no inclusion fence is uploaded", - self.test_fence_breach_no_return_point_no_inclusion), - - ("FenceDisableUnderAction", - "Tests Disabling fence while undergoing action caused by breach", - self.test_fence_disable_under_breach_action), - - ("ADSB", - "Test ADSB", - self.ADSB), - - ("SimADSB", - "Test SIM_ADSB", - self.SimADSB), - - ("Button", - "Test Buttons", - self.test_button), - - ("FRSkySPort", - "Test FrSky SPort mode", - self.test_frsky_sport), - - ("FRSkyPassThroughStatustext", - "Test FrSky PassThrough serial output - statustext", - self.FRSkyPassThroughStatustext), - - ("FRSkyPassThroughSensorIDs", - "Test FrSky PassThrough serial output - sensor ids", - self.FRSkyPassThroughSensorIDs), - - ("FRSkyMAVlite", - "Test FrSky MAVlite serial output", - self.test_frsky_mavlite), - - ("FRSkyD", - "Test FrSkyD serial output", - self.test_frsky_d), - - ("LTM", - "Test LTM serial output", - self.test_ltm), - - ("DEVO", - "Test DEVO serial output", - self.DEVO), - - ("AdvancedFailsafe", - "Test Advanced Failsafe", - self.test_advanced_failsafe), - - ("LOITER", - "Test Loiter mode", - self.LOITER), - - ("MAV_CMD_NAV_LOITER_TURNS", - "Test NAV_LOITER_TURNS mission item", - self.MAV_CMD_NAV_LOITER_TURNS), - - ("DeepStall", - "Test DeepStall Landing", - self.fly_deepstall), - - ("WatchdogHome", - "Ensure home is restored after watchdog reset", - self.WatchdogHome), - - ("LargeMissions", - "Test Manipulation of Large missions", - self.test_large_missions), - - ("Soaring", - "Test Soaring feature", - self.fly_soaring), - - ("Terrain", - "Test AP_Terrain", - self.Terrain), - - ("TerrainMission", - "Test terrain following in mission", - self.TerrainMission), - - ("TerrainLoiter", - "Test terrain following in loiter", - self.TerrainLoiter), - - ("VectorNavEAHRS", - "Test VectorNav EAHRS support", - self.test_vectornav), - - ("LordEAHRS", - "Test LORD Microstrain EAHRS support", - self.test_lord), - - ("Deadreckoning", - "Test deadreckoning support", - self.deadreckoning), - - ("DeadreckoningNoAirSpeed", - "Test deadreckoning support with no airspeed sensor", - self.deadreckoning_no_airspeed_sensor), - - ("EKFlaneswitch", - "Test EKF3 Affinity and Lane Switching", - self.ekf_lane_switch), - - ("AirspeedDrivers", - "Test AirSpeed drivers", - self.test_airspeed_drivers), - - ("RTL_CLIMB_MIN", - "Test RTL_CLIMB_MIN", - self.rtl_climb_min), - - ("ClimbBeforeTurn", - "Test climb-before-turn", - self.climb_before_turn), - - ("IMUTempCal", - "Test IMU temperature calibration", - self.test_imu_tempcal), - - ("MAV_DO_AUX_FUNCTION", - "Test triggering Auxiliary Functions via mavlink", - self.fly_aux_function), - - ("SmartBattery", - "Test smart battery logging etc", - self.SmartBattery), - - ("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), - - ("RCDisableAirspeedUse", - "Test RC DisableAirspeedUse option", - self.RCDisableAirspeedUse), - - ("AHRS_ORIENTATION", - "Test AHRS_ORIENTATION parameter", - self.AHRS_ORIENTATION), - - ("AHRSTrim", - "AHRS trim testing", - self.ahrstrim), - - ("Landing-Drift", - "Circuit with baro drift", - self.fly_landing_baro_drift), - - ("ForcedDCM", - "Switch to DCM mid-flight", - self.ForcedDCM), - - ("DCMFallback", - "Really annoy the EKF and force fallback", - self.DCMFallback), - - ("MAVFTP", - "Test MAVProxy can talk FTP to autopilot", - self.MAVFTP), - - ("AUTOTUNE", - "Test AutoTune mode", - self.AUTOTUNE), - - ("MegaSquirt", - "Test MegaSquirt EFI", - self.MegaSquirt), - - ("MSP_DJI", - "Test MSP DJI serial output", - self.test_msp_dji), - - ("SpeedToFly", - "Test soaring speed-to-fly", - self.fly_soaring_speed_to_fly), - - ("GlideSlopeThresh", - "Test rebuild glide slope if above and climbing", - self.test_glide_slope_threshold), - - ("LogUpload", - "Log upload", - self.log_upload), - - ("HIGH_LATENCY2", - "Set sending of HIGH_LATENCY2", - self.HIGH_LATENCY2), - - ("MidAirDisarmDisallowed", - "Ensure mid-air disarm is not possible", - self.MidAirDisarmDisallowed), - + self.AuxModeSwitch, + self.TestRCCamera, + self.TestRCRelay, + self.ThrottleFailsafe, + self.NeedEKFToArm, + self.ThrottleFailsafeFence, + self.TestFlaps, + self.DO_CHANGE_SPEED, + self.DO_REPOSITION, + self.GuidedRequest, + self.MainFlight, + self.TestGripperMission, + self.Parachute, + self.ParachuteSinkRate, + self.AIRSPEED_AUTOCAL, + self.RangeFinder, + self.FenceStatic, + self.FenceRTL, + self.FenceRTLRally, + self.FenceRetRally, + self.FenceAltCeilFloor, + self.FenceBreachedChangeMode, + self.FenceNoFenceReturnPoint, + self.FenceNoFenceReturnPointInclusion, + self.FenceDisableUnderAction, + self.ADSB, + self.SimADSB, + self.Button, + self.FRSkySPort, + self.FRSkyPassThroughStatustext, + self.FRSkyPassThroughSensorIDs, + self.FRSkyMAVlite, + self.FRSkyD, + self.LTM, + self.DEVO, + self.AdvancedFailsafe, + self.LOITER, + self.MAV_CMD_NAV_LOITER_TURNS, + self.DeepStall, + self.WatchdogHome, + self.LargeMissions, + self.Soaring, + self.Terrain, + self.TerrainMission, + self.TerrainLoiter, + self.VectorNavEAHRS, + self.LordEAHRS, + self.Deadreckoning, + self.DeadreckoningNoAirSpeed, + self.EKFlaneswitch, + self.AirspeedDrivers, + self.RTL_CLIMB_MIN, + self.ClimbBeforeTurn, + self.IMUTempCal, + self.MAV_DO_AUX_FUNCTION, + self.SmartBattery, + self.FlyEachFrame, + self.RCDisableAirspeedUse, + self.AHRS_ORIENTATION, + self.AHRSTrim, + self.LandingDrift, + self.ForcedDCM, + self.DCMFallback, + self.MAVFTP, + self.AUTOTUNE, + self.MegaSquirt, + self.MSP_DJI, + self.SpeedToFly, + self.GlideSlopeThresh, + self.LogUpload, + self.HIGH_LATENCY2, + self.MidAirDisarmDisallowed, ]) return ret def disabled_tests(self): return { - "Landing-Drift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", + "LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", } diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 47a186cdd8..d67f808069 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -103,9 +103,8 @@ class AutoTestSub(AutoTest): "Altitude not maintained: want %.2f (+/- %.2f) got=%.2f" % (previous_altitude, delta, m.alt)) - def test_alt_hold(self): - """Test ALT_HOLD mode - """ + def AltitudeHold(self): + """Test ALT_HOLD mode""" self.wait_ready_to_arm() self.arm_vehicle() self.change_mode('ALT_HOLD') @@ -167,7 +166,7 @@ class AutoTestSub(AutoTest): self.watch_altitude_maintained() self.disarm_vehicle() - def test_pos_hold(self): + def PositionHold(self): """Test POSHOLD mode""" self.wait_ready_to_arm() self.arm_vehicle() @@ -213,9 +212,8 @@ class AutoTestSub(AutoTest): raise NotAchievedException("Position Hold was unable to move north 2 meters, moved {} at {} degrees instead".format(distance_m, bearing)) # noqa self.disarm_vehicle() - def test_mot_thst_hover_ignore(self): - """Test if we are ignoring MOT_THST_HOVER parameter - """ + def MotorThrustHoverParameterIgnore(self): + """Test if we are ignoring MOT_THST_HOVER parameter""" # Test default parameter value mot_thst_hover_value = self.get_parameter("MOT_THST_HOVER") @@ -225,9 +223,10 @@ class AutoTestSub(AutoTest): # Test if parameter is being ignored for value in [0.25, 0.75]: self.set_parameter("MOT_THST_HOVER", value) - self.test_alt_hold() + self.AltitudeHold() - def dive_manual(self): + def DiveManual(self): + '''Dive manual''' self.wait_ready_to_arm() self.arm_vehicle() @@ -259,7 +258,9 @@ class AutoTestSub(AutoTest): if m.temperature != 2650: raise NotAchievedException("Did not get correct TSYS01 temperature") - def dive_mission(self, filename): + def DiveMission(self): + '''Dive mission''' + filename = "sub_mission.txt" self.progress("Executing mission %s" % filename) self.load_mission(filename) self.set_rc_default() @@ -274,7 +275,8 @@ class AutoTestSub(AutoTest): self.progress("Mission OK") - def test_gripper_mission(self): + def GripperMission(self): + '''Test gripper mission items''' try: self.get_parameter("GRIP_ENABLE", timeout=5) except NotAchievedException: @@ -289,7 +291,8 @@ class AutoTestSub(AutoTest): self.wait_statustext("Gripper Grabbed", timeout=60) self.wait_statustext("Gripper Released", timeout=60) - def dive_set_position_target(self): + def SET_POSITION_TARGET_GLOBAL_INT(self): + '''Move vehicle using SET_POSITION_TARGET_GLOBAL_INT''' self.change_mode('GUIDED') self.wait_ready_to_arm() self.arm_vehicle() @@ -376,6 +379,7 @@ class AutoTestSub(AutoTest): self.initialise_after_reboot_sitl() def DoubleCircle(self): + '''Test entering circle twice''' self.change_mode('CIRCLE') self.wait_ready_to_arm() self.arm_vehicle() @@ -400,36 +404,16 @@ class AutoTestSub(AutoTest): ret = super(AutoTestSub, self).tests() ret.extend([ - ("DiveManual", "Dive manual", self.dive_manual), - - ("AltitudeHold", "Test altitude holde mode", self.test_alt_hold), - ("PositionHold", "Test position hold mode", self.test_pos_hold), - - ("DiveMission", - "Dive mission", - lambda: self.dive_mission("sub_mission.txt")), - - ("GripperMission", - "Test gripper mission items", - self.test_gripper_mission), - - ("DoubleCircle", - "Test entering circle twice", - self.DoubleCircle), - - ("MotorThrustHoverParameterIgnore", "Test if we are ignoring MOT_THST_HOVER", self.test_mot_thst_hover_ignore), - - ("SET_POSITION_TARGET_GLOBAL_INT", - "Move vehicle using SET_POSITION_TARGET_GLOBAL_INT", - self.dive_set_position_target), - - ("TestLogDownloadMAVProxy", - "Test Onboard Log Download using MAVProxy", - self.test_log_download_mavproxy), - - ("LogUpload", - "Upload logs", - self.log_upload), + self.DiveManual, + self.AltitudeHold, + self.PositionHold, + self.DiveMission, + self.GripperMission, + self.DoubleCircle, + self.MotorThrustHoverParameterIgnore, + self.SET_POSITION_TARGET_GLOBAL_INT, + self.TestLogDownloadMAVProxy, + self.LogUpload, ]) return ret diff --git a/Tools/autotest/balancebot.py b/Tools/autotest/balancebot.py index 0528e14ff1..1c3d7b6da0 100644 --- a/Tools/autotest/balancebot.py +++ b/Tools/autotest/balancebot.py @@ -31,7 +31,8 @@ class AutoTestBalanceBot(AutoTestRover): self.frame = 'balancebot' super(AutoTestBalanceBot, self).init() - def test_do_set_mode_via_command_long(self): + def DO_SET_MODE(self): + '''Set mode via MAV_COMMAND_DO_SET_MODE''' self.do_set_mode_via_command_long("HOLD") self.do_set_mode_via_command_long("MANUAL") @@ -48,13 +49,14 @@ class AutoTestBalanceBot(AutoTestRover): '''balancebot tends to wander backwards, away from the target''' return 8 - def drive_rtl_mission(self): + def DriveRTL(self): + '''Drive an RTL Mission''' # if we Hold then the balancebot continues to wander # indefinitely at ~1m/s, hence we set to Acro self.set_parameter("MIS_DONE_BEHAVE", 2) - super(AutoTestBalanceBot, self).drive_rtl_mission() + super(AutoTestBalanceBot, self).DriveRTL() - def test_wheelencoders(self): + def TestWheelEncoder(self): '''make sure wheel encoders are generally working''' ex = None try: @@ -95,6 +97,10 @@ class AutoTestBalanceBot(AutoTestRover): if ex is not None: raise ex + def DriveMission(self): + '''Drive Mission rover1.txt''' + self.drive_mission("balancebot1.txt", strict=False) + def tests(self): '''return list of all tests''' @@ -103,32 +109,13 @@ inherit Rover's tests!''' ret = AutoTest.tests(self) ret.extend([ - - ("DriveRTL", - "Drive an RTL Mission", - self.drive_rtl_mission), - - ("DriveMission", - "Drive Mission %s" % "balancebot1.txt", - lambda: self.drive_mission("balancebot1.txt", strict=False)), - - ("TestWheelEncoder", - "Test wheel encoders", - self.test_wheelencoders), - - ("GetBanner", "Get Banner", self.do_get_banner), - - ("DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE", - self.test_do_set_mode_via_command_long), - - ("ServoRelayEvents", - "Test ServoRelayEvents", - self.test_servorelayevents), - - ("LogUpload", - "Upload logs", - self.log_upload), + self.DriveRTL, + self.DriveMission, + self.TestWheelEncoder, + self.GetBanner, + self.DO_SET_MODE, + self.ServoRelayEvents, + self.LogUpload, ]) return ret diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 899d4c62fa..e95d2c015f 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1435,9 +1435,11 @@ class LocationInt(object): class Test(object): '''a test definition - information about a test''' - def __init__(self, name, description, function, attempts=1, speedup=None): - self.name = name - self.description = description + def __init__(self, function, attempts=1, speedup=None): + self.name = function.__name__ + self.description = function.__doc__ + if self.description is None: + raise ValueError("%s is missing a docstring" % self.name) self.function = function self.attempts = attempts self.speedup = speedup @@ -2432,8 +2434,8 @@ class AutoTest(ABC): return ids - def test_onboard_logging_generation(self): - '''just generates, as we can't do a lot of testing''' + def LoggerDocumentation(self): + '''Test Onboard Logging Generation''' xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml") parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py') try: @@ -3036,7 +3038,8 @@ class AutoTest(ABC): if ex is not None: raise ex - def test_log_download(self): + def LogDownload(self): + '''Test Onboard Log Download''' if self.is_tracker(): # tracker starts armed, which is annoying return @@ -3625,14 +3628,15 @@ class AutoTest(ABC): if len(post_arming_list) <= len(pre_arming_list): raise NotAchievedException("Did not get a log on forced arm") - def test_onboard_logging(self): + def Logging(self): + '''Test Onboard Logging''' if self.is_tracker(): return self.onboard_logging_forced_arm() self.onboard_logging_log_disarmed() self.onboard_logging_not_log_disarmed() - def test_log_download_mavproxy(self, upload_logs=False): + def TestLogDownloadMAVProxy(self, upload_logs=False): """Download latest log.""" filename = "MAVProxy-downloaded-log.BIN" mavproxy = self.start_mavproxy() @@ -3647,7 +3651,8 @@ class AutoTest(ABC): self.mavproxy_unload_module(mavproxy, 'log') self.stop_mavproxy(mavproxy) - def log_upload(self): + def LogUpload(self): + '''upload logs to ArduPilot firmware server''' self.progress("Log upload disabled as CI artifacts are good") return if len(self.fail_list) > 0 and os.getenv("AUTOTEST_UPLOAD"): @@ -4687,7 +4692,8 @@ class AutoTest(ABC): return def CPUFailsafe(self): - '''Most vehicles just disarm on failsafe''' + '''Ensure we do something appropriate when the main loop stops''' + # Most vehicles just disarm on failsafe # customising the SITL commandline ensures the process will # get stopped/started at the end of the test if self.frame is None: @@ -5487,7 +5493,8 @@ class AutoTest(ABC): m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10) return m.capabilities - def test_get_autopilot_capabilities(self): + def GetCapabilities(self): + '''Get Capabilities''' self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT) self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION) @@ -7742,7 +7749,8 @@ Also, ignores heartbeats not from our target system''' self.progress("GroundSpeed OK (got=%f) (want=%f)" % (m.groundspeed, want)) - def fly_test_set_home(self): + def SetHome(self): + '''Setting and fetching of home''' if self.is_tracker(): # tracker starts armed... self.disarm_vehicle(force=True) @@ -7964,7 +7972,9 @@ Also, ignores heartbeats not from our target system''' for count in range(2, compass_count + 1): self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0}) - def test_mag_calibration(self, compass_count=3, timeout=1000): + # this autotest appears to interfere with FixedYawCalibration, no idea why. + def SITLCompassCalibration(self, compass_count=3, timeout=1000): + '''Test Fixed Yaw Calibration"''' def reset_pos_and_start_magcal(mavproxy, tmask): mavproxy.send("sitl_stop\n") mavproxy.send("sitl_attitude 0 0 0\n") @@ -8342,7 +8352,8 @@ Also, ignores heartbeats not from our target system''' raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" % (newkey, expected_value, current_value, str(transforms), key)) - def test_mag_reordering(self): + def CompassReordering(self): + '''Test Compass reordering when priorities are changed''' self.context_push() ex = None try: @@ -8444,7 +8455,10 @@ Also, ignores heartbeats not from our target system''' if ex is not None: raise ex - def test_fixed_yaw_calibration(self): + # something about SITLCompassCalibration appears to fail + # this one, so we put it first: + def FixedYawCalibration(self): + '''Test Fixed Yaw Calibration''' self.context_push() ex = None try: @@ -8537,7 +8551,8 @@ Also, ignores heartbeats not from our target system''' if ex is not None: raise ex - def test_dataflash_over_mavlink(self): + def DataFlashOverMAVLink(self): + '''Test DataFlash over MAVLink''' self.context_push() ex = None mavproxy = self.start_mavproxy() @@ -8602,8 +8617,8 @@ Also, ignores heartbeats not from our target system''' if ex is not None: raise ex - def test_dataflash_sitl(self): - """Test the basic functionality of block logging""" + def DataFlash(self): + """Test DataFlash SITL backend""" self.context_push() ex = None mavproxy = self.start_mavproxy() @@ -8699,7 +8714,7 @@ Also, ignores heartbeats not from our target system''' if herrors > header_errors: raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors)) - def test_dataflash_erase(self): + def DataFlashErase(self): """Test that erasing the dataflash chip and creating a new log is error free""" mavproxy = self.start_mavproxy() @@ -8781,8 +8796,8 @@ Also, ignores heartbeats not from our target system''' if ex is not None: raise ex - def test_arm_feature(self): - """Common feature to test.""" + def ArmFeatures(self): + '''Arm features''' # TEST ARMING/DISARM if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub(): raise ValueError("Arming check should be 1") @@ -9168,7 +9183,8 @@ Also, ignores heartbeats not from our target system''' if notachieved_ex is not None: raise notachieved_ex - def test_set_message_interval(self): + def SET_MESSAGE_INTERVAL(self): + '''Test MAV_CMD_SET_MESSAGE_INTERVAL''' self.start_subtest('Basic tests') self.test_set_message_interval_basic() self.start_subtest('Many-message tests') @@ -9322,7 +9338,8 @@ Also, ignores heartbeats not from our target system''' return msgs - def test_request_message(self, timeout=60): + def REQUEST_MESSAGE(self, timeout=60): + '''Test MAV_CMD_REQUEST_MESSAGE''' rate = round(self.get_message_rate("CAMERA_FEEDBACK", 10)) if rate != 0: raise PreconditionFailedException("Receiving camera feedback") @@ -9373,7 +9390,8 @@ Also, ignores heartbeats not from our target system''' def clear_fence(self): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE) - def test_config_error_loop(self): + # Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa + def ConfigErrorLoop(self): '''test the sensor config error loop works and that parameter sets are persistent''' parameter_name = "SERVO8_MIN" old_parameter_value = self.get_parameter(parameter_name) @@ -9415,7 +9433,8 @@ Also, ignores heartbeats not from our target system''' if self.get_parameter(parameter_name) != new_parameter_value: raise NotAchievedException("Parameter value did not stick") - def test_initial_mode(self): + def InitialMode(self): + '''Test initial mode switching''' if self.is_copter(): init_mode = (9, "LAND") if self.is_rover(): @@ -9438,7 +9457,8 @@ Also, ignores heartbeats not from our target system''' self.context_pop() self.reboot_sitl() - def test_gripper(self): + def Gripper(self): + '''Test gripper''' self.context_push() self.set_parameters({ "GRIP_ENABLE": 1, @@ -9589,7 +9609,7 @@ Also, ignores heartbeats not from our target system''' self.install_message_hook_context(check_terrain_requests) - def test_set_position_global_int(self, timeout=100): + def SetpointGlobalPos(self, timeout=100): """Test set position message in guided mode.""" # Disable heading and yaw test on rover type @@ -9812,7 +9832,7 @@ Also, ignores heartbeats not from our target system''' self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.disarm_vehicle() - def test_set_velocity_global_int(self, timeout=30): + def SetpointGlobalVel(self, timeout=30): """Test set position message in guided mode.""" # Disable heading and yaw rate test on rover type if self.is_rover(): @@ -10539,7 +10559,7 @@ switch value''' self.start_subsubtest("Check all parameters are documented") self.test_parameter_documentation_get_all_parameters() - def test_parameters(self): + def Parameters(self): '''general small tests for parameter system''' if self.is_balancebot(): # same binary and parameters as Rover @@ -10586,7 +10606,8 @@ switch value''' if m is not None: raise PreconditionFailedException("Receiving %s messags" % message) - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.assert_not_receiving_message('PID_TUNING', timeout=5) self.set_parameter("GCS_PID_MASK", 1) self.progress("making sure we are now getting PID_TUNING messages") @@ -10595,7 +10616,8 @@ switch value''' def sample_mission_filename(self): return "flaps.txt" - def test_advanced_failsafe(self): + def AdvancedFailsafe(self): + '''Test Advanced Failsafe''' self.context_push() ex = None try: @@ -10680,7 +10702,8 @@ switch value''' if m.fix_type >= fix_type: break - def nmea_output(self): + def NMEAOutput(self): + '''Test AHRS NMEA Output can be read by out NMEA GPS''' self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA self.customise_SITL_commandline([ @@ -10718,7 +10741,8 @@ switch value''' mavproxy.send("module unload %s\n" % module) mavproxy.expect("Unloaded module %s" % module) - def accelcal(self): + def AccelCal(self): + '''Accelerometer Calibration testing''' ex = None mavproxy = self.start_mavproxy() try: @@ -10872,14 +10896,16 @@ switch value''' self.context_pop() self.reboot_sitl() - def ahrstrim(self): + def AHRSTrim(self): + '''AHRS trim testing''' self.start_subtest("Attitude Correctness") self.ahrstrim_attitude_correctness() self.delay_sim_time(5) self.start_subtest("Preflight Calibration") self.ahrstrim_preflight_cal() - def test_button(self): + def Button(self): + '''Test Buttons''' self.set_parameter("SIM_PIN_MASK", 0) self.set_parameter("BTN_ENABLE", 1) self.drain_mav() @@ -11530,7 +11556,8 @@ switch value''' "Did not receive expected result in command_ack; want=%u got=%u" % (want_result, got_result)) - def test_frsky_mavlite(self): + def FRSkyMAVlite(self): + '''Test FrSky MAVlite serial output''' self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 @@ -11802,7 +11829,8 @@ switch value''' if rpm.rpm1 >= min_rpm: return - def test_frsky_sport(self): + def FRSkySPort(self): + '''Test FrSky SPort mode''' self.set_parameter("SERIAL5_PROTOCOL", 4) # serial5 is FRSky sport self.set_parameter("RPM1_TYPE", 10) # enable SITL RPM sensor self.customise_SITL_commandline([ @@ -11874,7 +11902,8 @@ switch value''' self.zero_throttle() self.disarm_vehicle(force=True) - def test_frsky_d(self): + def FRSkyD(self): + '''Test FrSkyD serial output''' self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 @@ -11995,7 +12024,8 @@ switch value''' # FIXME. Actually check the field values are correct :-) return True - def test_ltm(self): + def LTM(self): + '''Test LTM serial output''' self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 @@ -12036,6 +12066,7 @@ switch value''' return math.trunc(dd * 1.0e7) def DEVO(self): + '''Test DEVO serial output''' self.context_push() self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output self.customise_SITL_commandline([ @@ -12106,7 +12137,8 @@ switch value''' self.context_pop() self.reboot_sitl() - def test_msp_dji(self): + def MSP_DJI(self): + '''Test MSP DJI serial output''' self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode self.customise_SITL_commandline([ @@ -12130,7 +12162,8 @@ switch value''' if dist < 1: break - def test_crsf(self): + def CRSF(self): + '''Test RC CRSF''' self.context_push() ex = None try: @@ -12343,43 +12376,16 @@ switch value''' def tests(self): return [ - Test("PIDTuning", - "Test PID Tuning", - self.test_pid_tuning), - - Test("ArmFeatures", "Arm features", self.test_arm_feature), - - Test("SetHome", - "Test Set Home", - self.fly_test_set_home), - - Test("ConfigErrorLoop", - "Test Config Error Loop", - self.test_config_error_loop), - - Test("CPUFailsafe", - "Ensure we do something appropriate when the main loop stops", - self.CPUFailsafe), - - Test("Parameters", - "Test Parameter Set/Get", - self.test_parameters), - - Test("LoggerDocumentation", - "Test Onboard Logging Generation", - self.test_onboard_logging_generation), - - Test("Logging", - "Test Onboard Logging", - self.test_onboard_logging), - - Test("GetCapabilities", - "Get Capabilities", - self.test_get_autopilot_capabilities), - - Test("InitialMode", - "Test initial mode switching", - self.test_initial_mode), + self.PIDTuning, + self.ArmFeatures, + self.SetHome, + self.ConfigErrorLoop, + self.CPUFailsafe, + self.Parameters, + self.LoggerDocumentation, + self.Logging, + self.GetCapabilities, + self.InitialMode, ] def post_tests_announcements(self): @@ -12404,8 +12410,7 @@ switch value''' if type(test) == Test: all_tests.append(test) continue - (name, desc, func) = test - actual_test = Test(name, desc, func) + actual_test = Test(test) all_tests.append(actual_test) disabled = self.disabled_tests() diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 2c08334cc0..b7b1706fd6 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -57,7 +57,8 @@ class AutoTestHelicopter(AutoTestCopter): chan_pwm = (servo.servo1_raw + servo.servo2_raw + servo.servo3_raw)/3.0 return chan_pwm - def rotor_runup_complete_checks(self): + def RotorRunup(self): + '''Test rotor runip''' # Takeoff and landing in Loiter TARGET_RUNUP_TIME = 10 self.zero_throttle() @@ -91,8 +92,8 @@ class AutoTestHelicopter(AutoTestCopter): self.mav.wait_heartbeat() # fly_avc_test - fly AVC mission - def fly_avc_test(self): - # Arm + def AVCMission(self): + '''fly AVC mission''' self.change_mode('STABILIZE') self.wait_ready_to_arm() @@ -159,7 +160,8 @@ class AutoTestHelicopter(AutoTestCopter): self.hover() self.progress("TAKEOFF COMPLETE") - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -196,7 +198,7 @@ class AutoTestHelicopter(AutoTestCopter): self.progress("Setting hover collective") self.set_rc(3, 1500) - def fly_heli_poshold_takeoff(self): + def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() @@ -258,8 +260,8 @@ class AutoTestHelicopter(AutoTestCopter): if ex is not None: raise ex - def fly_heli_stabilize_takeoff(self): - """""" + def StabilizeTakeOff(self): + """Fly stabilize takeoff""" self.context_push() ex = None @@ -296,7 +298,7 @@ class AutoTestHelicopter(AutoTestCopter): if ex is not None: raise ex - def fly_spline_waypoint(self, timeout=600): + def SplineWaypoint(self, timeout=600): """ensure basic spline functionality works""" self.load_mission("copter_spline_mission.txt", strict=False) self.change_mode("LOITER") @@ -317,8 +319,8 @@ class AutoTestHelicopter(AutoTestCopter): self.progress("Lowering rotor speed") self.set_rc(8, 1000) - def fly_autorotation(self, timeout=600): - """ensure basic spline functionality works""" + def AutoRotation(self, timeout=600): + """Check engine-out behaviour""" self.set_parameter("AROT_ENABLE", 1) start_alt = 100 # metres self.set_parameter("PILOT_TKOFF_ALT", start_alt * 100) @@ -368,7 +370,8 @@ class AutoTestHelicopter(AutoTestCopter): self.set_rc(8, 1000) # Lower rotor speed # FIXME move this & plane's version to common - def test_airspeed_drivers(self, timeout=600): + def AirspeedDrivers(self, timeout=600): + '''Test AirSpeed drivers''' # set the start location to CMAC to use same test script as other vehicles self.sitl_start_loc = mavutil.location(-35.362881, 149.165222, 582.000000, 90.0) # CMAC @@ -428,39 +431,15 @@ class AutoTestHelicopter(AutoTestCopter): '''return list of all tests''' ret = AutoTest.tests(self) ret.extend([ - ("AVCMission", "Fly AVC mission", self.fly_avc_test), - - ("RotorRunUp", - "Test rotor runup", - self.rotor_runup_complete_checks), - - ("PosHoldTakeOff", - "Fly POSHOLD takeoff", - self.fly_heli_poshold_takeoff), - - ("StabilizeTakeOff", - "Fly stabilize takeoff", - self.fly_heli_stabilize_takeoff), - - ("SplineWaypoint", - "Fly Spline Waypoints", - self.fly_spline_waypoint), - - ("AutoRotation", - "Fly AutoRotation", - self.fly_autorotation), - - ("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), - - ("LogUpload", - "Log upload", - self.log_upload), - - ("AirspeedDrivers", - "Test AirSpeed drivers", - self.test_airspeed_drivers), + self.AVCMission, + self.RotorRunup, + self.PosHoldTakeOff, + self.StabilizeTakeOff, + self.SplineWaypoint, + self.AutoRotation, + self.FlyEachFrame, + self.LogUpload, + self.AirspeedDrivers, ]) return ret diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 1920c57e4b..af353e5090 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -88,7 +88,7 @@ class AutoTestQuadPlane(AutoTest): def set_autodisarm_delay(self, delay): self.set_parameter("LAND_DISARMDELAY", delay) - def test_airmode(self): + def AirMode(self): """Check that plane.air_mode turns on and off as required""" self.progress("########## Testing AirMode operation") self.set_parameter("AHRS_EKF_TYPE", 10) @@ -255,7 +255,7 @@ class AutoTestQuadPlane(AutoTest): self.disarm_vehicle(force=True) self.wait_ready_to_arm() - def test_motor_mask(self): + def TestMotorMask(self): """Check operation of output_motor_mask""" """copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)""" if not(int(self.get_parameter('Q_TILT_MASK')) & 1): @@ -406,6 +406,7 @@ class AutoTestQuadPlane(AutoTest): self.mav.motors_disarmed_wait() def EXTENDED_SYS_STATE(self): + '''Check extended sys state works''' self.EXTENDED_SYS_STATE_SLT() def fly_qautotune(self): @@ -566,7 +567,7 @@ class AutoTestQuadPlane(AutoTest): return freq - def fly_gyro_fft(self): + def GyroFFT(self): """Use dynamic harmonic notch to control motor noise.""" # basic gyro sample rate test self.progress("Flying with gyro FFT - Gyro sample rate") @@ -677,11 +678,13 @@ class AutoTestQuadPlane(AutoTest): if ex is not None: raise ex - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.change_mode("FBWA") # we don't update PIDs in MANUAL - super(AutoTestQuadPlane, self).test_pid_tuning() + super(AutoTestQuadPlane, self).PIDTuning() - def test_parameter_checks(self): + def ParameterChecks(self): + '''basic parameter checks''' self.test_parameter_checks_poscontrol("Q_P") def rc_defaults(self): @@ -701,6 +704,7 @@ class AutoTestQuadPlane(AutoTest): } def BootInAUTO(self): + '''Test behaviour when booting in auto''' self.load_mission("mission.txt") self.set_parameters({ }) @@ -722,7 +726,8 @@ class AutoTestQuadPlane(AutoTest): self.change_mode('QLAND') self.wait_disarmed(timeout=60) - def test_pilot_yaw(self): + def PilotYaw(self): + '''Test pilot yaw in various modes''' self.takeoff(10, mode="QLOITER") self.set_parameter("STICK_MIXING", 0) self.set_rc(4, 1700) @@ -734,7 +739,8 @@ class AutoTestQuadPlane(AutoTest): self.set_rc(4, 1500) self.do_RTL() - def weathervane_test(self): + def Weathervane(self): + '''test nose-into-wind functionality''' # We test nose into wind code paths and yaw direction in copter autotest, # so we shall test the side into wind yaw direction and plane code paths here. self.set_parameters({"SIM_WIND_SPD": 10, @@ -759,7 +765,8 @@ class AutoTestQuadPlane(AutoTest): '''In lockup Plane should copy RC inputs to RC outputs''' self.plane_CPUFailsafe() - def test_qassist(self): + def QAssist(self): + '''QuadPlane Assist tests''' # find a motor peak self.takeoff(10, mode="QHOVER") self.set_rc(3, 1800) @@ -812,7 +819,7 @@ class AutoTestQuadPlane(AutoTest): self.change_mode("RTL") self.wait_disarmed(timeout=300) - def tailsitter(self): + def Tailsitter(self): '''tailsitter test''' self.set_parameter('Q_FRAME_CLASS', 10) self.set_parameter('Q_ENABLE', 1) @@ -835,6 +842,7 @@ class AutoTestQuadPlane(AutoTest): self.disarm_vehicle() def ICEngine(self): + '''Test ICE Engine support''' rc_engine_start_chan = 11 self.set_parameters({ 'SERVO13_FUNCTION': 67, # ignition @@ -870,6 +878,7 @@ class AutoTestQuadPlane(AutoTest): self.reboot_sitl() def ICEngineMission(self): + '''Test ICE Engine Mission support''' rc_engine_start_chan = 11 self.set_parameters({ 'SERVO13_FUNCTION': 67, # ignition @@ -887,6 +896,7 @@ class AutoTestQuadPlane(AutoTest): self.wait_disarmed(timeout=300) def Ship(self): + '''Ensure we can take off from simulated ship''' self.context_push() self.set_parameters({ 'SIM_SHIP_ENABLE': 1, @@ -906,6 +916,7 @@ class AutoTestQuadPlane(AutoTest): self.reboot_sitl() def MidAirDisarmDisallowed(self): + '''Check disarm behaviour in Q-mode''' self.start_subtest("Basic arm in qloiter") self.set_parameter("FLIGHT_OPTIONS", 0) self.change_mode('QLOITER') @@ -956,76 +967,35 @@ class AutoTestQuadPlane(AutoTest): self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1) self.disarm_vehicle() + def Mission(self): + '''fly the OBC 2016 mission in Dalby''' + self.fly_mission( + "Dalby-OBC2016.txt", + "Dalby-OBC2016-fence.txt", + include_terrain_timeout=True + ) + def tests(self): '''return list of all tests''' ret = super(AutoTestQuadPlane, self).tests() ret.extend([ - ("TestAirMode", "Test airmode", self.test_airmode), - - ("TestMotorMask", "Test output_motor_mask", self.test_motor_mask), - - ("PilotYaw", - "Test pilot yaw in various modes", - self.test_pilot_yaw), - - ("ParameterChecks", - "Test Arming Parameter Checks", - self.test_parameter_checks), - - ("TestLogDownload", - "Test Onboard Log Download", - self.test_log_download), - - ("EXTENDED_SYS_STATE", - "Check extended sys state works", - self.EXTENDED_SYS_STATE), - - ("Mission", "Dalby Mission", - lambda: self.fly_mission( - "Dalby-OBC2016.txt", - "Dalby-OBC2016-fence.txt", - include_terrain_timeout=True - ) - ), - - ("Weathervane", - "Test Weathervane Functionality", - self.weathervane_test), - - ("QAssist", - "QuadPlane Assist tests", - self.test_qassist), - - ("GyroFFT", "Fly Gyro FFT", - self.fly_gyro_fft), - - ("Tailsitter", - "Test tailsitter support", - self.tailsitter), - - ("ICEngine", - "Test ICE Engine support", - self.ICEngine), - - ("ICEngineMission", - "Test ICE Engine Mission support", - self.ICEngineMission), - - ("MidAirDisarmDisallowed", - "Check disarm behaviour in Q-mode", - self.MidAirDisarmDisallowed), - - ("BootInAUTO", - "Test behaviour when booting in auto", - self.BootInAUTO), - - ("Ship", - "Ensure we can take off from simulated ship", - self.Ship), - - ("LogUpload", - "Log upload", - self.log_upload), + self.AirMode, + self.TestMotorMask, + self.PilotYaw, + self.ParameterChecks, + self.LogDownload, + self.EXTENDED_SYS_STATE, + self.Mission, + self.Weathervane, + self.QAssist, + self.GyroFFT, + self.Tailsitter, + self.ICEngine, + self.ICEngineMission, + self.MidAirDisarmDisallowed, + self.BootInAUTO, + self.Ship, + self.LogUpload, ]) return ret diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index ebd650a649..6aaf6b89a2 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -83,8 +83,8 @@ class AutoTestRover(AutoTest): # TESTS DRIVE ########################################################## # Drive a square in manual mode - def drive_square(self, side=50): - """Drive a square, Driving N then E .""" + def DriveSquare(self, side=50): + """Learn/Drive Square with Ch7 option""" self.context_push() ex = None @@ -235,7 +235,7 @@ class AutoTestRover(AutoTest): # "timed out after %u seconds" % timeout) # return False - def test_sprayer(self): + def Sprayer(self): """Test sprayer functionality.""" self.context_push() ex = None @@ -354,8 +354,8 @@ class AutoTestRover(AutoTest): if ex: raise ex - def drive_max_rcin(self, timeout=30): - """Test max RC inputs""" + def DriveMaxRCIN(self, timeout=30): + """Drive rover at max RC inputs""" self.context_push() ex = None @@ -404,7 +404,12 @@ class AutoTestRover(AutoTest): self.disarm_vehicle() self.progress("Mission OK") - def test_gripper_mission(self): + def DriveMission(self): + '''Drive Mission rover1.txt''' + self.drive_mission("rover1.txt", strict=False) + + def GripperMission(self): + '''Test Gripper Mission Items''' self.load_mission("rover-gripper-mission.txt") self.change_mode('AUTO') self.wait_ready_to_arm() @@ -415,7 +420,8 @@ class AutoTestRover(AutoTest): self.wait_statustext("Mission Complete", timeout=60, check_context=True) self.disarm_vehicle() - def do_get_banner(self): + def GetBanner(self): + '''Get Banner''' target_sysid = self.sysid_thismav() target_compid = 1 self.mav.mav.command_long_send( @@ -480,7 +486,8 @@ class AutoTestRover(AutoTest): return delta - def drive_brake(self): + def DriveBrake(self): + '''Test braking''' self.set_parameters({ 'CRUISE_SPEED': 15, 'ATC_BRAKE': 0, @@ -514,7 +521,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) '''maximum distance allowed from home at end''' return 6.5 - def drive_rtl_mission(self, timeout=120): + def DriveRTL(self, timeout=120): + '''Drive an RTL Mission''' self.wait_ready_to_arm() self.arm_vehicle() @@ -564,7 +572,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() self.progress("RTL Mission OK (%fm)" % home_distance) - def drive_fence_ac_avoidance(self): + def AC_Avoidance(self): + '''Test AC Avoidance switch''' self.context_push() ex = None try: @@ -602,7 +611,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex: raise ex - def test_servorelayevents(self): + def ServoRelayEvents(self): + '''Test ServoRelayEvents''' self.do_set_relay(0, 0) off = self.get_parameter("SIM_PIN_MASK") self.do_set_relay(0, 1) @@ -612,7 +622,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) "Pin mask unchanged after relay cmd") self.progress("Pin mask changed after relay command") - def test_setting_modes_via_mavproxy_switch(self): + def MAVProxy_SetModeUsingSwitch(self): + """Set modes via mavproxy switch""" self.customise_SITL_commandline([ "--rc-in-port", "5502", ]) @@ -643,7 +654,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_setting_modes_via_mavproxy_mode_command(self): + def MAVProxy_SetModeUsingMode(self): + '''Set modes via mavproxy mode command''' fnoo = [(1, 'ACRO'), (3, 'STEERING'), (4, 'HOLD'), @@ -660,8 +672,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.wait_mode(expected) self.stop_mavproxy(mavproxy) - def test_setting_modes_via_modeswitch(self): - # test setting of modes through mode switch + def ModeSwitch(self): + ''''Set modes via modeswitch''' self.context_push() ex = None try: @@ -688,7 +700,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_setting_modes_via_auxswitches(self): + def AuxModeSwitch(self): + '''Set modes via auxswitches''' self.context_push() ex = None try: @@ -731,7 +744,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_rc_override_cancel(self): + def RCOverridesCancel(self): + '''Test RC overrides Cancel''' self.set_parameter("SYSID_MYGCS", self.mav.source_system) self.change_mode('MANUAL') self.wait_ready_to_arm() @@ -801,7 +815,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) break self.disarm_vehicle() - def test_rc_overrides(self): + def RCOverrides(self): + '''Test RC overrides''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) ex = None @@ -1044,7 +1059,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_manual_control(self): + def MANUAL_CONTROL(self): + '''Test mavlink MANUAL_CONTROL''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) ex = None @@ -1134,6 +1150,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) raise ex def CameraMission(self): + '''Test Camera Mission Items''' self.load_mission("rover-camera-mission.txt") self.wait_ready_to_arm() self.change_mode("AUTO") @@ -1170,17 +1187,20 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() - def test_do_set_mode_via_command_long(self): + def DO_SET_MODE(self): + '''Set mode via MAV_COMMAND_DO_SET_MODE''' self.do_set_mode_via_command_long("HOLD") self.do_set_mode_via_command_long("MANUAL") - def test_mavproxy_do_set_mode_via_command_long(self): + def MAVProxy_DO_SET_MODE(self): + '''Set mode using MAVProxy commandline DO_SET_MODE''' mavproxy = self.start_mavproxy() self.mavproxy_do_set_mode_via_command_long(mavproxy, "HOLD") self.mavproxy_do_set_mode_via_command_long(mavproxy, "MANUAL") self.stop_mavproxy(mavproxy) - def test_sysid_enforce(self): + def SYSID_ENFORCE(self): + '''Test enforcement of SYSID_MYGCS''' '''Run the same arming code with correct then incorrect SYSID''' if self.mav.source_system != self.mav.mav.srcSystem: @@ -1240,6 +1260,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) raise ex def Rally(self): + '''Test Rally Points''' self.load_rally("rover-test-rally.txt") self.wait_ready_to_arm() @@ -1984,7 +2005,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) # MANUAL> usage: fence # noqa - def test_gcs_fence(self): + def GCSFence(self): + '''Upload and download of fence''' target_system = 1 target_component = 1 @@ -2154,8 +2176,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) # exclusion zones) # FIXME: add test that a fence with edges that cross can't be uploaded # FIXME: add a test that fences enclose an area (e.g. all the points aren't the same value! - - def test_offboard(self, timeout=90): + def Offboard(self, timeout=90): + '''Test Offboard Control''' self.load_mission("rover-guided-mission.txt") self.wait_ready_to_arm(require_absolute=True) self.arm_vehicle() @@ -2408,8 +2430,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) mavutil.mavlink.MAV_MISSION_TYPE_RALLY, ) - def test_gcs_rally(self, target_system=1, target_component=1): - + def GCSRally(self, target_system=1, target_component=1): + '''Upload and download of rally using MAVProxy''' self.start_subtest("Testing mavproxy CLI for rally points") if not self.mavproxy_can_do_mision_item_protocols(): return @@ -2842,8 +2864,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) # MANUAL> usage: rally # noqa - def test_rally(self, target_system=1, target_component=1): - + def RallyUploadDownload(self, target_system=1, target_component=1): + '''Upload and download of rally''' old_srcSystem = self.mav.mav.srcSystem self.drain_mav() @@ -3428,7 +3450,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) raise e self.reboot_sitl() - def test_gcs_mission(self): + def GCSMission(self): '''check MAVProxy's waypoint handling of missions''' target_system = 1 target_component = 1 @@ -4341,7 +4363,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) raise NotAchievedException("Items did not survive reboot (want=%u got=%u)" % (8, downloaded_len)) - def test_poly_fence(self): + def PolyFence(self): '''test fence-related functions''' target_system = 1 target_component = 1 @@ -4531,7 +4553,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) target_system=target_system, target_component=target_component) - def drive_smartrtl(self): + def SmartRTL(self): + '''Test SmartRTL''' self.change_mode("STEERING") self.wait_ready_to_arm() self.arm_vehicle() @@ -4562,8 +4585,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() - def test_motor_test(self): - '''AKA run-rover-run''' + def MotorTest(self): + '''Motor Test triggered via mavlink''' magic_throttle_value = 1812 self.wait_ready_to_arm() self.run_cmd( @@ -4677,7 +4700,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_wheelencoders(self): + def WheelEncoders(self): '''make sure wheel encoders are generally working''' ex = None try: @@ -4810,7 +4833,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.change_mode("RTL") self.wait_distance_to_home(distance_min, distance_max, timeout=timeout) - def test_poly_fence_avoidance(self, target_system=1, target_component=1): + def PolyFenceAvoidance(self, target_system=1, target_component=1): + '''PolyFence avoidance tests''' self.change_mode("LOITER") self.wait_ready_to_arm() self.arm_vehicle() @@ -4861,7 +4885,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_poly_fence_object_avoidance_bendy_ruler_easier(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceBendyRulerEasier(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - easier bendy ruler test''' if not self.mavproxy_can_do_mision_item_protocols(): return self.test_poly_fence_object_avoidance_auto_bendy_ruler_easier( @@ -4955,7 +4980,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_poly_fence_object_avoidance(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidance(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests''' if not self.mavproxy_can_do_mision_item_protocols(): return @@ -4966,7 +4992,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) target_system=target_system, target_component=target_component) - def test_poly_fence_object_avoidance_bendy_ruler(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceBendyRuler(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - bendy ruler''' if not self.mavproxy_can_do_mision_item_protocols(): return # bendy Ruler isn't as flexible as Dijkstra for planning, so @@ -5086,7 +5113,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_scripting_steering_and_throttle(self): + def ScriptingSteeringAndThrottle(self): + '''Scripting test - steering and throttle''' self.start_subtest("Scripting square") ex = None example_script = "rover-set-steering-and-throttle.lua" @@ -5197,7 +5225,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_scripting(self): + def Scripting(self): + '''Scripting test''' self.test_scripting_set_home_to_vehicle_location() self.test_scripting_print_home_and_origin() self.test_scripting_hello_world() @@ -5247,7 +5276,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.check_mission_upload_download(items) - def test_mission_frames(self, target_system=1, target_component=1): + def MissionFrames(self, target_system=1, target_component=1): + '''Upload/Download of items in different frames''' for frame in (mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT, mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, @@ -5330,7 +5360,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.progress("Have now seen all expected messages") break - def ap_proximity_mav(self): + def AP_Proximity_MAV(self): + '''Test MAV proximity backend''' self.context_push() ex = None try: @@ -5391,7 +5422,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_send_to_components(self): + def SendToComponents(self): + '''Test ArduPilot send_to_components function''' self.progress("Introducing ourselves to the autopilot as a component") old_srcSystem = self.mav.mav.srcSystem self.mav.mav.srcSystem = 1 @@ -5432,7 +5464,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) raise NotAchievedException("Did not get correct command_id") break - def test_skid_steer(self): + def SkidSteer(self): + '''Check skid-steering''' model = "rover-skid" self.customise_SITL_commandline([], @@ -5461,7 +5494,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.zero_throttle() self.disarm_vehicle() - def test_slew_rate(self): + def SlewRate(self): """Test Motor Slew Rate feature.""" self.context_push() self.change_mode("MANUAL") @@ -5538,6 +5571,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.context_pop() def SET_ATTITUDE_TARGET(self, target_sysid=None, target_compid=1): + '''Test handling of SET_ATTITUDE_TARGET''' if target_sysid is None: target_sysid = self.sysid_thismav() self.change_mode('GUIDED') @@ -5571,6 +5605,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() def SET_POSITION_TARGET_LOCAL_NED(self, target_sysid=None, target_compid=1): + '''Test handling of SET_POSITION_TARGET_LOCAL_NED''' if target_sysid is None: target_sysid = self.sysid_thismav() self.change_mode('GUIDED') @@ -5618,7 +5653,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.do_RTL() self.disarm_vehicle() - def test_end_mission_behavior(self, timeout=60): + def EndMissionBehavior(self, timeout=60): + '''Test end mission behavior''' self.context_push() ex = None try: @@ -5691,7 +5727,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if ex is not None: raise ex - def test_mavproxy_param(self): + def MAVProxyParam(self): + '''Test MAVProxy parameter handling''' mavproxy = self.start_mavproxy() mavproxy.send("param fetch\n") mavproxy.expect("Received [0-9]+ parameters") @@ -5750,6 +5787,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) ]) def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1): + '''Test handling of CMD_DO_SET_MISSION_CURRENT''' if target_sysid is None: target_sysid = self.sysid_thismav() self.check_mission_upload_download(self.MAV_CMD_DO_SET_MISSION_CURRENT_mission()) @@ -5772,6 +5810,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) want_result=mavutil.mavlink.MAV_RESULT_FAILED) def FlashStorage(self): + '''Test flash storage (for parameters etc)''' self.set_parameter("LOG_BITMASK", 1) self.reboot_sitl() @@ -5793,6 +5832,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.assert_parameter_value("LOG_BITMASK", 1) def FRAMStorage(self): + '''Test FRAM storage (for parameters etc)''' self.set_parameter("LOG_BITMASK", 1) self.reboot_sitl() @@ -5815,6 +5855,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.assert_parameter_value("LOG_BITMASK", 1) def RangeFinder(self): + '''Test RangeFinder''' # the following magic numbers correspond to the post locations in SITL home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 315) @@ -5837,7 +5878,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) if abs(m.distance - want_range) > 0.1: raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance)) - def test_depthfinder(self): + def DepthFinder(self): + '''Test mulitple depthfinders for boats''' # Setup rangefinders self.customise_SITL_commandline([ "--uartH=sim:nmea", # NMEA Rangefinder @@ -5911,6 +5953,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) # self.context_pop() def EStopAtBoot(self): + '''Ensure EStop prevents arming when asserted at boot time''' self.context_push() self.set_parameters({ "RC9_OPTION": 31, @@ -5934,6 +5977,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.assert_mode(want) def StickMixingAuto(self): + '''Ensure Stick Mixing works in auto''' items = [] self.set_parameter('STICK_MIXING', 1) # home @@ -5953,6 +5997,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.disarm_vehicle() def AutoDock(self): + '''Test automatic docking of rover for multiple FOVs of simulated beacon''' self.context_push() self.set_parameters({ @@ -6021,259 +6066,71 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) ret = super(AutoTestRover, self).tests() ret.extend([ - ("MAVProxy_SetModeUsingSwitch", - "Set modes via mavproxy switch", - self.test_setting_modes_via_mavproxy_switch), - - ("HIGH_LATENCY2", - "Set sending of HIGH_LATENCY2", - self.HIGH_LATENCY2), - - ("MAVProxy_SetModeUsingMode", - "Set modes via mavproxy mode command", - self.test_setting_modes_via_mavproxy_mode_command), - - ("ModeSwitch", - "Set modes via modeswitch", - self.test_setting_modes_via_modeswitch), - - ("AuxModeSwitch", - "Set modes via auxswitches", - self.test_setting_modes_via_auxswitches), - - ("DriveRTL", - "Drive an RTL Mission", self.drive_rtl_mission), - - ("SmartRTL", - "Test SmartRTL", - self.drive_smartrtl), - - ("DriveSquare", - "Learn/Drive Square with Ch7 option", - self.drive_square), - - ("DriveMaxRCIN", - "Drive rover at max RC inputs", - self.drive_max_rcin), - - ("DriveMission", - "Drive Mission %s" % "rover1.txt", - lambda: self.drive_mission("rover1.txt", strict=False)), - - # disabled due to frequent failures in travis. This test needs re-writing - # ("Drive Brake", self.drive_brake), - - ("GetBanner", "Get Banner", self.do_get_banner), - - ("DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE", - self.test_do_set_mode_via_command_long), - - ("MAVProxy_DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE with MAVProxy", - self.test_mavproxy_do_set_mode_via_command_long), - - ("ServoRelayEvents", - "Test ServoRelayEvents", - self.test_servorelayevents), - - ("RCOverrides", "Test RC overrides", self.test_rc_overrides), - - ("RCOverridesCancel", "Test RC overrides Cancel", self.test_rc_override_cancel), - - ("MANUAL_CONTROL", "Test mavlink MANUAL_CONTROL", self.test_manual_control), - - ("Sprayer", "Test Sprayer", self.test_sprayer), - - ("AC_Avoidance", - "Test AC Avoidance switch", - self.drive_fence_ac_avoidance), - - ("CameraMission", - "Test Camera Mission Items", - self.CameraMission), - - # Gripper test - ("Gripper", - "Test gripper", - self.test_gripper), - - ("GripperMission", - "Test Gripper Mission Items", - self.test_gripper_mission), - - ("SET_MESSAGE_INTERVAL", - "Test MAV_CMD_SET_MESSAGE_INTERVAL", - self.test_set_message_interval), - - ("REQUEST_MESSAGE", - "Test MAV_CMD_REQUEST_MESSAGE", - self.test_request_message), - - ("SYSID_ENFORCE", - "Test enforcement of SYSID_MYGCS", - self.test_sysid_enforce), - - ("SET_ATTITUDE_TARGET", - "Test handling of SET_ATTITUDE_TARGET", - self.SET_ATTITUDE_TARGET), - - ("SET_POSITION_TARGET_LOCAL_NED", - "Test handling of SET_POSITION_TARGET_LOCAL_NED", - self.SET_POSITION_TARGET_LOCAL_NED), - - ("MAV_CMD_DO_SET_MISSION_CURRENT", - "Test handling of CMD_DO_SET_MISSION_CURRENT", - self.MAV_CMD_DO_SET_MISSION_CURRENT), - - ("Button", - "Test Buttons", - self.test_button), - - ("Rally", - "Test Rally Points", - self.Rally), - - ("Offboard", - "Test Offboard Control", - self.test_offboard), - - ("MAVProxyParam", - "Test MAVProxy parameter handling", - self.test_mavproxy_param), - - ("GCSFence", - "Upload and download of fence", - self.test_gcs_fence), - - ("Rally", - "Upload and download of rally", - self.test_rally), - - ("GCSMission", - "Upload and download of mission", - self.test_gcs_mission), - - ("GCSRally", - "Upload and download of rally using MAVProxy", - self.test_gcs_rally), - - ("MotorTest", - "Motor Test triggered via mavlink", - self.test_motor_test), - - ("WheelEncoders", - "Ensure SITL wheel encoders work", - self.test_wheelencoders), - - ("DataFlashOverMAVLink", - "Test DataFlash over MAVLink", - self.test_dataflash_over_mavlink), - - ("DataFlashSITL", - "Test DataFlash SITL backend", - self.test_dataflash_sitl), - - ("SkidSteer", - "Check skid-steering", - self.test_skid_steer), - - ("PolyFence", - "PolyFence tests", - self.test_poly_fence), - - ("PolyFenceAvoidance", - "PolyFence avoidance tests", - self.test_poly_fence_avoidance), - - ("PolyFenceObjectAvoidance", - "PolyFence object avoidance tests", - self.test_poly_fence_object_avoidance), - - ("PolyFenceObjectAvoidanceBendyRuler", - "PolyFence object avoidance tests - bendy ruler", - self.test_poly_fence_object_avoidance_bendy_ruler), - - ("SendToComponents", - "Test ArduPilot send_to_components function", - self.test_send_to_components), - - ("PolyFenceObjectAvoidanceBendyRulerEasier", - "PolyFence object avoidance tests - easier bendy ruler test", - self.test_poly_fence_object_avoidance_bendy_ruler_easier), - - ("SlewRate", - "Test output slew rate", - self.test_slew_rate), - - ("Scripting", - "Scripting test", - self.test_scripting), - - ("ScriptingSteeringAndThrottle", - "Scripting test - steering and throttle", - self.test_scripting_steering_and_throttle), - - ("MissionFrames", - "Upload/Download of items in different frames", - self.test_mission_frames), - - ("SetpointGlobalPos", - "Test setpoint global position", - lambda: self.test_set_position_global_int()), - - ("SetpointGlobalVel", - "Test setpoint gloabl velocity", - lambda: self.test_set_velocity_global_int()), - - ("AccelCal", - "Accelerometer Calibration testing", - self.accelcal), - - ("RangeFinder", - "Test RangeFinder", - self.RangeFinder), - - ("AP_Proximity_MAV", - "Test MAV proximity backend", - self.ap_proximity_mav), - - ("EndMissionBehavior", - "Test end mission behavior", - self.test_end_mission_behavior), - - ("FlashStorage", - "Test flash storage (for parameters etc)", - self.FlashStorage), - - ("FRAMStorage", - "Test FRAM storage (for parameters etc)", - self.FRAMStorage), - - ("LogUpload", - "Upload logs", - self.log_upload), - - ("DepthFinder", - "Test mulitple depthfinders for boats", - self.test_depthfinder), - - ("ChangeModeByNumber", - "Test changing mode by number", - self.ChangeModeByNumber), - - ("EStopAtBoot", - "Ensure EStop prevents arming when asserted at boot time", - self.EStopAtBoot), - - ("StickMixingAuto", - "Ensure Stick Mixing works in auto", - self.StickMixingAuto), - - ("AutoDock", - "Test automatic docking of rover for multiple FOVs of simulated beacon", - self.AutoDock), - + self.MAVProxy_SetModeUsingSwitch, + self.HIGH_LATENCY2, + self.MAVProxy_SetModeUsingMode, + self.ModeSwitch, + self.AuxModeSwitch, + self.DriveRTL, + self.SmartRTL, + self.DriveSquare, + self.DriveMaxRCIN, + self.DriveMission, + # self.DriveBrake, # disabled due to frequent failures + self.GetBanner, + self.DO_SET_MODE, + self.MAVProxy_DO_SET_MODE, + self.ServoRelayEvents, + self.RCOverrides, + self.RCOverridesCancel, + self.MANUAL_CONTROL, + self.Sprayer, + self.AC_Avoidance, + self.CameraMission, + self.Gripper, + self.GripperMission, + self.SET_MESSAGE_INTERVAL, + self.REQUEST_MESSAGE, + self.SYSID_ENFORCE, + self.SET_ATTITUDE_TARGET, + self.SET_POSITION_TARGET_LOCAL_NED, + self.MAV_CMD_DO_SET_MISSION_CURRENT, + self.Button, + self.Rally, + self.Offboard, + self.MAVProxyParam, + self.GCSFence, + self.GCSMission, + self.GCSRally, + self.MotorTest, + self.WheelEncoders, + self.DataFlashOverMAVLink, + self.DataFlash, + self.SkidSteer, + self.PolyFence, + self.PolyFenceAvoidance, + self.PolyFenceObjectAvoidance, + self.PolyFenceObjectAvoidanceBendyRuler, + self.SendToComponents, + self.PolyFenceObjectAvoidanceBendyRulerEasier, + self.SlewRate, + self.Scripting, + self.ScriptingSteeringAndThrottle, + self.MissionFrames, + self.SetpointGlobalPos, + self.SetpointGlobalVel, + self.AccelCal, + self.RangeFinder, + self.AP_Proximity_MAV, + self.EndMissionBehavior, + self.FlashStorage, + self.FRAMStorage, + self.LogUpload, + self.DepthFinder, + self.ChangeModeByNumber, + self.EStopAtBoot, + self.StickMixingAuto, + self.AutoDock, ]) return ret diff --git a/Tools/autotest/sailboat.py b/Tools/autotest/sailboat.py index 02c2b3ba28..a67fe0a5ad 100644 --- a/Tools/autotest/sailboat.py +++ b/Tools/autotest/sailboat.py @@ -32,7 +32,8 @@ class AutoTestSailboat(AutoTestRover): self.frame = 'sailboat' super(AutoTestSailboat, self).init() - def drive_rtl_mission(self, timeout=120): + def DriveRTL(self, timeout=120): + '''Drive an RTL Mission''' self.wait_ready_to_arm() self.arm_vehicle() @@ -74,19 +75,17 @@ class AutoTestSailboat(AutoTestRover): self.progress("RTL Mission OK") + def DriveMission(self): + '''sail a simple mission''' + self.drive_mission("balancebot1.txt", strict=False) + def tests(self): '''return list of all tests''' ret = ([]) ret.extend([ - ("DriveRTL", - "Drive an RTL Mission", - self.drive_rtl_mission), - - ("DriveMission", - "Drive Mission %s" % "balancebot1.txt", - lambda: self.drive_mission("balancebot1.txt", strict=False)), - + self.DriveRTL, + self.DriveMission, ]) return ret