From 9f313ca315cfd139ecc5a20b875f483fa90041aa Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Tue, 21 May 2024 19:34:43 +0200 Subject: [PATCH] autotest: New tests An autotest for a catapult launch has been added for Plane. Larger maximum pitch limit has been allowed, to demonstrate pitch behaviour. TKOFF_LVL_ALT=30 has been selected, to demonstrate the new TECS behaviour. An auxiliary `set_servo` method has been added to `vehicle_test_suite.py`. An autotest for TAKEOFF mode has been added for Plane. Added new takeoff autotest --- .../CatapultTakeoff/catapult.txt | 13 +++ Tools/autotest/arduplane.py | 84 +++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 4 + 3 files changed, 101 insertions(+) create mode 100644 Tools/autotest/ArduPlane_Tests/CatapultTakeoff/catapult.txt diff --git a/Tools/autotest/ArduPlane_Tests/CatapultTakeoff/catapult.txt b/Tools/autotest/ArduPlane_Tests/CatapultTakeoff/catapult.txt new file mode 100644 index 00000000000000..0aa9cd624db827 --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/CatapultTakeoff/catapult.txt @@ -0,0 +1,13 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1 +1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 100.000000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 100.000000 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 100.000000 1 +4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1 +5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1 +6 0 0 177 2.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1 +8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1 +9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1 +10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1 +11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index ba7a2eed20db4a..a03226004d98bd 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4160,6 +4160,88 @@ def LandingDrift(self): self.wait_disarmed(timeout=180) + def CatapultTakeoff(self): + '''Test that a catapult takeoff works correctly''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "TKOFF_LVL_ALT": 30.0, + "TKOFF_THR_MINACC": 3.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + "RTL_AUTOLAND": 2, # The mission contains a DO_LAND_START item. + }) + + # Record desired target speed. + speed_cruise = self.get_parameter("AIRSPEED_CRUISE") + + # Load and start mission. + self.load_mission("catapult.txt", strict=True) + self.change_mode('AUTO') + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Wait until we're midway through the climb. + test_alt = 50 + self.wait_altitude(test_alt, test_alt+2, relative=True) + + # Ensure that by then the aircraft does not overspeed. + self.wait_airspeed(speed_cruise-2, speed_cruise+2, minimum_duration=2, timeout=4) + + # Wait for landing waypoint. + self.wait_current_waypoint(11, timeout=1200) + self.wait_disarmed(120) + + def TakeoffMinThrottle(self): + '''Test that the minimum throttle during the first takeoff stage. + + If TKOFF_LVL_ALT is set and TKOFF_THR_MAX is set, then the throttle + should TKOFF_THR_MAX until the aircraft reaches TKOFF_LVL_ALT. This + might cause overspeed, but is desirable. + ''' + + self.customise_SITL_commandline( + [], + model='plane-catapult', + defaults_filepath=self.model_defaults_filepath("plane") + ) + self.set_parameters({ + "TKOFF_LVL_ALT": 30.0, + "TKOFF_ALT": 100.0, + "TKOFF_THR_MINACC": 3.0, + "TKOFF_THR_MAX": 90.0, + "TECS_PITCH_MAX": 35.0, + "PTCH_LIM_MAX_DEG": 35.0, + }) + self.change_mode("TAKEOFF") + + self.wait_ready_to_arm() + self.arm_vehicle() + + # Throw the catapult. + self.set_servo(7, 2000) + + # Wait until we've climbed past min airspeed but before TKOFF_LVL_ALT. + test_alt = self.get_parameter("TKOFF_LVL_ALT") + self.wait_altitude(test_alt-5, test_alt, relative=True) + + # Ensure that by then the aircraft still goes full throttle. + self.assert_servo_channel_value(3, 1000+10*self.get_parameter("TKOFF_THR_MAX")) + + # Wait for the takeoff to complete. + target_alt = self.get_parameter("TKOFF_ALT") + self.wait_altitude(target_alt-5, target_alt, relative=True) + + self.fly_home_land_and_disarm() + def DCMFallback(self): '''Really annoy the EKF and force fallback''' self.reboot_sitl() @@ -5426,6 +5508,8 @@ def tests(self): self.AHRS_ORIENTATION, self.AHRSTrim, self.LandingDrift, + self.CatapultTakeoff, + self.TakeoffMinThrottle, self.ForcedDCM, self.DCMFallback, self.MAVFTP, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index b20e4dc37b4e33..f28bbaa71a0188 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -5406,6 +5406,10 @@ def set_rc(self, chan, pwm, timeout=20): """Setup a simulated RC control to a PWM value""" self.set_rc_from_map({chan: pwm}, timeout=timeout) + def set_servo(self, chan, pwm): + """Replicate the functionality of MAVProxy: servo set """ + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm) + def location_offset_ne(self, location, north, east): '''move location in metres''' print("old: %f %f" % (location.lat, location.lng))