From 8a7555bf56be0842efc35b43143a189db840cdd8 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 10 Oct 2018 15:07:21 +0200 Subject: [PATCH] Tools: autotest: fix up the arming tests Tools: unify arm function failure message Tools: get autodisarm time from parameter for autodisarm test Tools: disable autodisarm for arm/disarm tests. Tools: fix interlock channel for heli Tools: simplify arming_test sub exclusion Tools: fix empty string in progress Tools: add back arming test to plane Tools: allow single test run on Sub Tools: remove old comments on autotest common Tools: add vehicle type getter function Tools: make get_rudder_channel abstract method Tools: common make get_disarm_delay abstract method Tools: make set_autodisarm_delay abstract method Tools: rename set_throttle_zero to zero_throttle and use it Tools: common.py remove unnecessary exception Tools: subclass vehicle type --- Tools/autotest/apmrover2.py | 39 +---- Tools/autotest/arducopter.py | 51 ++++-- Tools/autotest/arduplane.py | 14 ++ Tools/autotest/ardusub.py | 3 + Tools/autotest/autotest.py | 1 + Tools/autotest/common.py | 321 ++++++++++++----------------------- Tools/autotest/quadplane.py | 31 ++-- 7 files changed, 179 insertions(+), 281 deletions(-) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 85d949cde3..51c757ab6f 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -102,40 +102,11 @@ class AutoTestRover(AutoTest): self.progress("Ready to start testing!") - # def reset_and_arm(self): - # """Reset RC, set to MANUAL and arm.""" - # self.wait_heartbeat() - # # ensure all sticks in the middle - # self.set_rc_default() - # self.mavproxy.send('switch 1\n') - # self.wait_heartbeat() - # self.disarm_vehicle() - # self.wait_heartbeat() - # self.arm_vehicle() - # + def is_rover(self): + return True - # # TEST RC OVERRIDE - # # TEST RC OVERRIDE TIMEOUT - # def test_rtl(self, home, distance_min=5, timeout=250): - # """Return, land.""" - # super(AutoTestRover, self).test_rtl(home, distance_min, timeout) - # - # def test_mission(self, filename): - # """Test a mission from a file.""" - # self.progress("Test mission %s" % filename) - # num_wp = self.load_mission(filename) - # self.mavproxy.send('wp set 1\n') - # self.wait_heartbeat() - # self.mavproxy.send('switch 4\n') # auto mode - # self.wait_mode('AUTO') - # ret = self.wait_waypoint(0, num_wp-1, max_dist=5, timeout=500) - # - # if ret: - # self.mavproxy.expect("Mission Complete") - # self.wait_heartbeat() - # self.wait_mode('HOLD') - # self.progress("test: MISSION COMPLETE: passed=%s" % ret) - # return ret + def get_rudder_channel(self): + return int(self.get_parameter("RCMAP_ROLL")) ########################################################## # TESTS DRIVE @@ -665,7 +636,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) def test_rc_override_cancel(self): self.change_mode('MANUAL') self.wait_ready_to_arm() - self.set_throttle_zero() + self.zero_throttle() self.arm_vehicle() # start moving forward a little: normal_rc_throttle = 1700 diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 5ebedd17c4..a79870cb81 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -125,6 +125,18 @@ class AutoTestCopter(AutoTest): if self.copy_tlog: shutil.copy(self.logfile, self.buildlog) + def is_copter(self): + return True + + def get_rudder_channel(self): + return int(self.get_parameter("RCMAP_YAW")) + + def get_disarm_delay(self): + return int(self.get_parameter("DISARM_DELAY")) + + def set_autodisarm_delay(self, delay): + self.set_parameter("DISARM_DELAY", delay) + def user_takeoff(self, alt_min=30): '''takeoff using mavlink takeoff command''' self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, @@ -151,7 +163,7 @@ class AutoTestCopter(AutoTest): if not self.armed(): self.progress("Waiting reading for arm") self.wait_ready_to_arm(require_absolute=require_absolute) - self.set_rc(3, 1000) + self.zero_throttle() self.arm_vehicle() self.set_rc(3, takeoff_throttle) self.wait_for_alt(alt_min=alt_min, timeout=timeout) @@ -491,7 +503,7 @@ class AutoTestCopter(AutoTest): self.mav.motors_disarmed_wait() self.progress("Reached failsafe home OK") self.change_mode('STABILIZE') - self.set_rc(3, 1000) + self.zero_throttle() return self.reboot_sitl() @@ -612,13 +624,13 @@ class AutoTestCopter(AutoTest): self.set_parameter("FENCE_ENABLE", 0) if (alt <= 1 and home_distance < 10) or (not self.armed() and home_distance < 10): # reduce throttle - self.set_rc(3, 1000) + self.zero_throttle() self.change_mode("LAND") self.progress("Waiting for disarm") self.mav.motors_disarmed_wait() self.progress("Reached home OK") self.change_mode("STABILIZE") - self.set_rc(3, 1000) + self.zero_throttle() # remove if we ever clear battery failsafe flag on disarm: self.mavproxy.send('arm uncheck all\n') self.arm_vehicle() @@ -670,7 +682,7 @@ class AutoTestCopter(AutoTest): self.progress("Waiting for disarm") self.mav.motors_disarmed_wait() - self.set_rc(3, 1000) + self.zero_throttle() self.mavproxy.send('switch 6\n') # stabilize mode self.wait_mode('STABILIZE') @@ -824,7 +836,7 @@ class AutoTestCopter(AutoTest): self.change_mode("STABILIZE") self.wait_ready_to_arm() - self.set_rc(3, 1000) + self.zero_throttle() self.arm_vehicle() # switch into AUTO mode and raise throttle @@ -1201,7 +1213,7 @@ class AutoTestCopter(AutoTest): self.wait_waypoint(0, num_wp-1, timeout=500) # set throttle to minimum - self.set_rc(3, 1000) + self.zero_throttle() # wait for disarm self.mav.motors_disarmed_wait() @@ -1243,7 +1255,7 @@ class AutoTestCopter(AutoTest): self.wait_waypoint(0, num_wp-1, timeout=500) # set throttle to minimum - self.set_rc(3, 1000) + self.zero_throttle() # wait for disarm self.mav.motors_disarmed_wait() @@ -1444,7 +1456,7 @@ class AutoTestCopter(AutoTest): ex = e self.context_pop() - self.set_rc(3, 1000) + self.zero_throttle() self.reboot_sitl() if ex is not None: @@ -1535,7 +1547,7 @@ class AutoTestCopter(AutoTest): self.progress("Exception caught") ex = e - self.set_rc(3, 1000) + self.zero_throttle() if ex is not None: raise ex @@ -1690,7 +1702,7 @@ class AutoTestCopter(AutoTest): self.progress("Waiting for location") old_pos = self.mav.location() - self.set_rc(3, 1000) + self.zero_throttle() self.takeoff(10, 1800) # move away a little self.set_rc(2, 1550) @@ -1709,7 +1721,7 @@ class AutoTestCopter(AutoTest): self.progress("Exception caught") ex = e - self.set_rc(3, 1000) + self.zero_throttle() self.context_pop() self.reboot_sitl() self.progress("All done") @@ -1911,7 +1923,7 @@ class AutoTestCopter(AutoTest): self.progress("Exception caught") ex = e - self.set_rc(3, 1000) + self.zero_throttle() if ex is not None: raise ex @@ -1971,7 +1983,7 @@ class AutoTestCopter(AutoTest): self.progress("Exception caught") ex = e - self.set_rc(3, 1000) + self.zero_throttle() if ex is not None: raise ex @@ -2154,7 +2166,7 @@ class AutoTestCopter(AutoTest): self.progress("Waiting for location") self.mav.location() - self.set_rc(3, 1000) + self.zero_throttle() self.mavproxy.send('switch 6\n') # stabilize mode self.wait_heartbeat() self.wait_mode('STABILIZE') @@ -2218,7 +2230,7 @@ class AutoTestCopter(AutoTest): ex = e self.context_pop() - self.set_rc(3, 1000) + self.zero_throttle() self.reboot_sitl() if ex is not None: @@ -2590,7 +2602,7 @@ class AutoTestCopter(AutoTest): self.progress("Waiting for location") self.mav.location() - self.set_rc(3, 1000) + self.zero_throttle() self.mavproxy.send('switch 6\n') # stabilize mode self.wait_heartbeat() self.wait_mode('STABILIZE') @@ -2627,7 +2639,7 @@ class AutoTestCopter(AutoTest): ex = e self.context_pop() - self.set_rc(3, 1000) + self.zero_throttle() self.reboot_sitl() self.progress("All done") @@ -2817,6 +2829,9 @@ class AutoTestHeli(AutoTestCopter): AVCHOME.heading) self.frame = 'heli' + def is_heli(self): + return True + def rc_defaults(self): ret = super(AutoTestHeli, self).rc_defaults() ret[8] = 1000 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 7ca369797b..02004eb3be 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -93,6 +93,18 @@ class AutoTestPlane(AutoTest): self.hasInit = True self.progress("Ready to start testing!") + def is_plane(self): + return True + + def get_rudder_channel(self): + return int(self.get_parameter("RCMAP_YAW")) + + def get_disarm_delay(self): + return int(self.get_parameter("LAND_DISARMDELAY")) + + def set_autodisarm_delay(self, delay): + self.set_parameter("LAND_DISARMDELAY", delay) + def takeoff(self): """Takeoff get to 30m altitude.""" @@ -752,6 +764,8 @@ class AutoTestPlane(AutoTest): ("TestFlaps", "Flaps", self.fly_flaps), + ("ArmFeatures", "Arm features", self.test_arm_feature), + ("MainFlight", "Lots of things in one flight", self.test_main_flight), diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index c8694aea2d..ff38c2e0e0 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -95,6 +95,9 @@ class AutoTestSub(AutoTest): self.progress("Ready to start testing!") + def is_sub(self): + return True + def dive_manual(self): self.wait_ready_to_arm() self.arm_vehicle() diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 32dcd55ee3..bd15240833 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -306,6 +306,7 @@ def run_specific_test(step, *args, **kwargs): "drive.APMrover2": apmrover2.AutoTestRover, "drive.BalanceBot": balancebot.AutoTestBalanceBot, "fly.CopterAVC": arducopter.AutoTestHeli, + "dive.ArduSub": ardusub.AutoTestSub, } tester_class = tester_class_map[testname] tester = tester_class(*args, **kwargs) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 6c3373e38a..eaf2ccc8dd 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -683,9 +683,9 @@ class AutoTest(ABC): return True raise SetRCTimeout("Failed to send RC commands to channel %s" % str(chan)) - def set_throttle_zero(self): + def zero_throttle(self): """Set throttle to zero.""" - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: + if self.is_rover(): self.set_rc(3, 1500) else: self.set_rc(3, 1000) @@ -716,19 +716,12 @@ class AutoTest(ABC): self.set_rc(chan, out_trim) def get_rudder_channel(self): - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: - return int(self.get_parameter("RCMAP_YAW")) - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_FIXED_WING: - return int(self.get_parameter("RCMAP_YAW")) - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: - return int(self.get_parameter("RCMAP_ROLL")) - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_SUBMARINE: - raise ErrorException("Arming with rudder is not supported by Submarine") + """Return the Rudder channel number as set in parameter.""" + raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame)) + + def get_disarm_delay(self): + """Return disarm delay value.""" + raise ErrorException("Disarm delay is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame)) def armed(self): """Return true if vehicle is armed and safetyoff""" @@ -752,7 +745,7 @@ class AutoTest(ABC): if self.mav.motors_armed(): self.progress("Motors ARMED") return True - raise AutoTestTimeoutException("Unable to ARM with mavlink") + raise AutoTestTimeoutException("Failed to ARM with mavlink") def disarm_vehicle(self, timeout=20): """Disarm vehicle with mavlink disarm message.""" @@ -772,7 +765,7 @@ class AutoTest(ABC): if not self.mav.motors_armed(): self.progress("Motors DISARMED") return True - raise AutoTestTimeoutException("Unable to DISARM with mavlink") + raise AutoTestTimeoutException("Failed to DISARM with mavlink") def mavproxy_arm_vehicle(self): """Arm vehicle with mavlink arm message send from MAVProxy.""" @@ -807,7 +800,7 @@ class AutoTest(ABC): print("Not armed after %f seconds" % (tdelta)) if tdelta > timeout: break - self.progress("FAILED TO ARM WITH RADIO") + self.progress("Failed to ARM with radio") self.set_output_to_trim(self.get_rudder_channel()) return False @@ -824,7 +817,7 @@ class AutoTest(ABC): self.set_output_to_trim(self.get_rudder_channel()) self.progress("Disarm in %ss" % disarm_delay) # TODO check disarming time return True - self.progress("FAILED TO DISARM WITH RADIO") + self.progress("Failed to DISARM with radio") self.set_output_to_trim(self.get_rudder_channel()) return False @@ -838,7 +831,7 @@ class AutoTest(ABC): if self.mav.motors_armed(): self.progress("MOTORS ARMED OK WITH SWITCH") return True - self.progress("FAILED TO ARM WITH SWITCH") + self.progress("Failed to ARM with switch") return False def disarm_motors_with_switch(self, switch_chan, timeout=20): @@ -851,26 +844,28 @@ class AutoTest(ABC): if not self.mav.motors_armed(): self.progress("MOTORS DISARMED OK WITH SWITCH") return True - self.progress("FAILED TO DISARM WITH SWITCH") + self.progress("Failed to DISARM with switch") return False - def autodisarm_motors(self): - """Autodisarm motors.""" - self.progress("Autodisarming motors") - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: # NOT IMPLEMENTED ON ROVER - self.progress("MOTORS AUTODISARMED OK") - return True + def wait_autodisarm_motors(self): + """Wait for Autodisarm motors within disarm delay + this feature is only available in copter (DISARM_DELAY) and plane (LAND_DISARMDELAY).""" + self.progress("Wait autodisarming motors") + disarm_delay = self.get_disarm_delay() tstart = self.get_sim_time() - timeout = 15 + timeout = disarm_delay * 2 while self.get_sim_time() < tstart + timeout: self.wait_heartbeat() if not self.mav.motors_armed(): - disarm_delay = self.get_sim_time() - tstart + disarm_time = self.get_sim_time() - tstart self.progress("MOTORS AUTODISARMED") - self.progress("Autodisarm in %ss" % disarm_delay) # TODO check disarming time - return True - self.progress("FAILED TO AUTODISARM") - return False + self.progress("Autodisarm in %ss, expect less than %ss" % (disarm_time, disarm_delay)) + return disarm_time <= disarm_delay + raise AutoTestTimeoutException("Failed to AUTODISARM") + + def set_autodisarm_delay(self, delay): + """Set autodisarm delay""" + raise ErrorException("Auto disarm is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame)) @staticmethod def should_fetch_all_for_parameter_change(param_name): @@ -1115,20 +1110,15 @@ class AutoTest(ABC): def reach_heading_manual(self, heading): """Manually direct the vehicle to the target heading.""" - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: + if self.is_copter(): self.mavproxy.send('rc 4 1580\n') self.wait_heading(heading) self.mavproxy.send('rc 4 1500\n') self.mav.recv_match(condition='RC_CHANNELS.chan4_raw==1500', blocking=True) - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_FIXED_WING: + if self.is_plane(): self.progress("NOT IMPLEMENTED") - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: + if self.is_rover(): self.mavproxy.send('rc 1 1700\n') self.mavproxy.send('rc 3 1550\n') self.wait_heading(heading) @@ -1141,20 +1131,15 @@ class AutoTest(ABC): def reach_distance_manual(self, distance): """Manually direct the vehicle to the target distance from home.""" - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: + if self.is_copter(): self.mavproxy.send('rc 2 1350\n') self.wait_distance(distance, accuracy=5, timeout=60) self.mavproxy.send('rc 2 1500\n') self.mav.recv_match(condition='RC_CHANNELS.chan2_raw==1500', blocking=True) - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_FIXED_WING: + if self.is_plane(): self.progress("NOT IMPLEMENTED") - if self.mav.mav_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER: + if self.is_rover(): self.mavproxy.send('rc 3 1700\n') self.wait_distance(distance, accuracy=2) self.mavproxy.send('rc 3 1500\n') @@ -1503,7 +1488,6 @@ class AutoTest(ABC): if text.lower() in m.text.lower(): self.progress("Received expected text : %s" % m.text.lower()) return True - self.progress() raise AutoTestTimeoutException("Failed to received text : %s" % text.lower()) @@ -1645,11 +1629,15 @@ class AutoTest(ABC): # TEST ARMING/DISARM self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests interlock_channel = 8 # Plane got flighmode_ch on channel 8 - if self.mav.mav_type is not mavutil.mavlink.MAV_TYPE_HELICOPTER: # heli don't need interlock option + if not self.is_heli(): # heli don't need interlock option interlock_channel = 9 self.set_parameter("RC%u_OPTION" % interlock_channel, 32) self.set_rc(interlock_channel, 1000) - self.set_throttle_zero() + self.zero_throttle() + # Disable auto disarm for next tests + # Rover and Sub don't have auto disarm + if self.is_copter() or self.is_plane(): + self.set_autodisarm_delay(0) self.start_test("Test normal arm and disarm features") self.wait_ready_to_arm() self.progress("default arm_vehicle() call") @@ -1664,7 +1652,8 @@ class AutoTest(ABC): self.progress("disarm with mavproxy") if not self.mavproxy_disarm_vehicle(): raise NotAchievedException("Failed to DISARM") - if self.mav.mav_type != mavutil.mavlink.MAV_TYPE_SUBMARINE: + + if not self.is_sub(): self.progress("arm with rc input") if not self.arm_motors_with_rc_input(): raise NotAchievedException("Failed to arm with RC input") @@ -1672,19 +1661,6 @@ class AutoTest(ABC): if not self.disarm_motors_with_rc_input(): raise NotAchievedException("Failed to disarm with RC input") - # Disable auto disarm for next test - # Rover and Sub don't have auto disarm - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: - self.set_parameter("DISARM_DELAY", 0) - elif self.mav.mav_type == mavutil.mavlink.MAV_TYPE_FIXED_WING: - self.set_parameter("LAND_DISARMDELAY", 0) - # Sub has no 'switches' - if self.mav.mav_type != mavutil.mavlink.MAV_TYPE_SUBMARINE: self.start_test("Test arm and disarm with switch") arming_switch = 7 self.set_parameter("RC%d_OPTION" % arming_switch, 41) @@ -1696,31 +1672,24 @@ class AutoTest(ABC): if not self.disarm_motors_with_switch(arming_switch): raise NotAchievedException("Failed to disarm with switch") self.set_rc(arming_switch, 1000) - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: - self.start_test("Test arming failure with throttle too high") - self.set_rc(3, 1800) - try: - if self.arm_vehicle(): - raise NotAchievedException("Armed when throttle too high") - except AutoTestTimeoutException(): - pass - except ValueError: - pass - if self.arm_motors_with_rc_input(): - raise NotAchievedException( - "Armed via RC when throttle too high") - if self.arm_motors_with_switch(arming_switch): - raise NotAchievedException("Armed via RC when switch too high") - self.set_throttle_zero() - self.set_rc(arming_switch, 1000) - # Sub doesn't have 'stick commands' - if self.mav.mav_type != mavutil.mavlink.MAV_TYPE_SUBMARINE: + if self.is_copter(): + self.start_test("Test arming failure with throttle too high") + self.set_rc(3, 1800) + try: + if self.arm_vehicle(): + raise NotAchievedException("Armed when throttle too high") + except ValueError: + pass + if self.arm_motors_with_rc_input(): + raise NotAchievedException( + "Armed via RC when throttle too high") + if self.arm_motors_with_switch(arming_switch): + raise NotAchievedException("Armed via RC when switch too high") + self.zero_throttle() + self.set_rc(arming_switch, 1000) + + # Sub doesn't have 'stick commands' self.start_test("Test arming failure with ARMING_RUDDER=0") self.set_parameter("ARMING_RUDDER", 0) if self.arm_motors_with_rc_input(): @@ -1743,51 +1712,45 @@ class AutoTest(ABC): self.wait_heartbeat() self.set_parameter("ARMING_RUDDER", 2) - if self.mav.mav_type in [mavutil.mavlink.MAV_TYPE_QUADROTOR, - mavutil.mavlink.MAV_TYPE_HELICOPTER, - mavutil.mavlink.MAV_TYPE_HEXAROTOR, - mavutil.mavlink.MAV_TYPE_OCTOROTOR, - mavutil.mavlink.MAV_TYPE_COAXIAL, - mavutil.mavlink.MAV_TYPE_TRICOPTER]: - self.start_test("Test arming failure with interlock enabled") - self.set_rc(interlock_channel, 2000) - if self.arm_motors_with_rc_input(): - raise NotAchievedException( - "Armed with RC input when interlock enabled") - if self.arm_motors_with_switch(arming_switch): - raise NotAchievedException( - "Armed with switch when interlock enabled") - self.disarm_vehicle() - self.wait_heartbeat() - self.set_rc(arming_switch, 1000) - self.set_rc(interlock_channel, 1000) - if self.mav.mav_type is mavutil.mavlink.MAV_TYPE_HELICOPTER: - self.start_test("Test motor interlock enable can't be set while disarmed") + if self.is_copter(): + self.start_test("Test arming failure with interlock enabled") self.set_rc(interlock_channel, 2000) - channel_field = "servo%u_raw" % interlock_channel - interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel) - tstart = self.get_sim_time() - while True: - if self.get_sim_time_cached() - tstart > 20: - self.set_rc(8, 1000) - break # success! - m = self.mav.recv_match(type='SERVO_OUTPUT_RAW', - blocking=True, - timeout=2) - if m is None: - continue - m_value = getattr(m, channel_field, None) - if m_value is None: - self.set_rc(8, 1000) - raise ValueError("Message has no %s field" % - channel_field) - self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" % - (channel_field, m_value, interlock_value)) - if m_value != interlock_value: - self.set_rc(8, 1000) - raise NotAchievedException("Motor interlock was changed while disarmed") - - self.set_rc(8, 1000) + if self.arm_motors_with_rc_input(): + raise NotAchievedException( + "Armed with RC input when interlock enabled") + if self.arm_motors_with_switch(arming_switch): + raise NotAchievedException( + "Armed with switch when interlock enabled") + self.disarm_vehicle() + self.wait_heartbeat() + self.set_rc(arming_switch, 1000) + self.set_rc(interlock_channel, 1000) + if self.is_heli(): + self.start_test("Test motor interlock enable can't be set while disarmed") + self.set_rc(interlock_channel, 2000) + channel_field = "servo%u_raw" % interlock_channel + interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel) + tstart = self.get_sim_time() + while True: + if self.get_sim_time_cached() - tstart > 20: + self.set_rc(interlock_channel, 1000) + break # success! + m = self.mav.recv_match(type='SERVO_OUTPUT_RAW', + blocking=True, + timeout=2) + if m is None: + continue + m_value = getattr(m, channel_field, None) + if m_value is None: + self.set_rc(interlock_channel, 1000) + raise ValueError("Message has no %s field" % + channel_field) + self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" % + (channel_field, m_value, interlock_value)) + if m_value != interlock_value: + self.set_rc(interlock_channel, 1000) + raise NotAchievedException("Motor interlock was changed while disarmed") + self.set_rc(interlock_channel, 1000) self.progress("ALL PASS") self.context_pop() # TODO : add failure test : arming check, wrong mode; Test arming magic; Same for disarm @@ -2021,81 +1984,21 @@ class AutoTest(ABC): )) self.context_pop() self.reboot_sitl() - # # TEST MISSION FILE - # # TODO : rework that to work on autotest server - # # self.progress("TEST LOADING MISSION") - # # num_wp = self.load_mission( - # os.path.join(testdir, "fake_mission.txt")) - # # if num_wp == 0: - # # self.progress("Failed to load all_msg_mission") - # # sucess = False - # # - # # self.progress("TEST SAVING MISSION") - # # num_wp_old = num_wp - # # num_wp = self.save_mission_to_file(os.path.join(testdir, - # "fake_mission2.txt")) - # # if num_wp != num_wp_old: - # # self.progress("Failed to save all_msg_mission") - # # sucess = False - # - # self.progress("TEST CLEARING MISSION") - # self.mavproxy.send("wp clear\n") - # self.mavproxy.send('wp list\n') - # self.mavproxy.expect('Requesting [0-9]+ waypoints') - # num_wp = mavwp.MAVWPLoader().count() - # if num_wp != 0: - # self.progress("Failed to clear mission ") - # sucess = False - # - # return sucess - # - # # TESTS FAILSAFE - # @abc.abstractmethod - # def test_throttle_failsafe(self, home, distance_min=10, side=60, - # timeout=180): - # """Test that RTL success in case of thottle failsafe.""" - # pass - # - # # TEST ARM RADIO - # @abc.abstractmethod - # def test_arm_motors_radio(self): - # """Test arming with RC sticks.""" - # pass - # - # # TEST DISARM RADIO - # @abc.abstractmethod - # def test_disarm_motors_radio(self): - # """Test disarming with RC sticks.""" - # pass - # - # # TEST AUTO DISARM - # @abc.abstractmethod - # def test_autodisarm_motors(self): - # """Test auto disarming.""" - # pass - # - # # TEST RC OVERRIDE - # # TEST RC OVERRIDE TIMEOUT - # @abc.abstractmethod - # def test_rtl(self, home, distance_min=10, timeout=250): - # """Test that RTL success.""" - # self.progress("# Enter RTL") - # self.mavproxy.send('switch 3\n') - # tstart = self.get_sim_time() - # while self.get_sim_time() < tstart + timeout: - # m = self.mav.recv_match(type='VFR_HUD', blocking=True) - # pos = self.mav.location() - # home_distance = self.get_distance(home, pos) - # self.progress("Alt: %u HomeDistance: %.0f" % - # (m.alt, home_distance)) - # if m.alt <= 1 and home_distance < distance_min: - # self.progress("RTL Complete") - # return True - # return False - # - # @abc.abstractmethod - # def test_mission(self, filename): - # pass + + def is_copter(self): + return False + + def is_sub(self): + return False + + def is_plane(self): + return False + + def is_rover(self): + return False + + def is_heli(self): + return False def initial_mode(self): '''return mode vehicle should start in with no RC inputs set''' diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 08e46ac6ac..24e3949faf 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -89,26 +89,17 @@ class AutoTestQuadPlane(AutoTest): self.hasInit = True self.progress("Ready to start testing!") - # def test_arm_motors_radio(self): - # super(AutotestQuadPlane, self).test_arm_motors_radio() - # - # def test_disarm_motors_radio(self): - # super(AutotestQuadPlane, self).test_disarm_motors_radio() - # - # def test_autodisarm_motors(self): - # super(AutotestQuadPlane, self).test_autodisarm_motors() - # - # def test_rtl(self, home, distance_min=10, timeout=250): - # super(AutotestQuadPlane, self).test_rtl(home, - # distance_min=10, timeout=250) - # - # def test_throttle_failsafe(self, home, distance_min=10, - # side=60, timeout=180): - # super(AutotestQuadPlane, self).test_throttle_failsafe(home, - # distance_min=10, side=60, timeout=180) - # - # def test_mission(self, filename): - # super(AutotestQuadPlane, self).test_mission(filename) + def is_plane(self): + return True + + def get_rudder_channel(self): + return int(self.get_parameter("RCMAP_YAW")) + + def get_disarm_delay(self): + return int(self.get_parameter("LAND_DISARMDELAY")) + + def set_autodisarm_delay(self, delay): + self.set_parameter("LAND_DISARMDELAY", delay) def fly_mission(self, filename, fence, height_accuracy=-1): """Fly a mission from a file."""