autotest: added non-compass takeoff test

This commit is contained in:
Andrew Tridgell 2024-11-25 15:39:37 +11:00
parent c15fa7b943
commit 42ad2a7911
2 changed files with 37 additions and 1 deletions

View File

@ -88,7 +88,7 @@ void ModeTakeoff::update()
const float groundspeed = groundspeed2d.length(); const float groundspeed = groundspeed2d.length();
// see if we will skip takeoff as already flying // see if we will skip takeoff as already flying
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) { if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && groundspeed > 3) {
if (altitude >= alt) { if (altitude >= alt) {
gcs().send_text(MAV_SEVERITY_INFO, "Above TKOFF alt - loitering"); gcs().send_text(MAV_SEVERITY_INFO, "Above TKOFF alt - loitering");
plane.next_WP_loc = plane.current_loc; plane.next_WP_loc = plane.current_loc;

View File

@ -4805,6 +4805,41 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.fly_home_land_and_disarm() self.fly_home_land_and_disarm()
def TakeoffTakeoff5(self):
'''Test the behaviour of a takeoff with no compass'''
self.set_parameters({
"COMPASS_USE": 0,
"COMPASS_USE2": 0,
"COMPASS_USE3": 0,
})
import copy
start_loc = copy.copy(SITL_START_LOCATION)
start_loc.heading = 175
self.customise_SITL_commandline(["--home=%.9f,%.9f,%.2f,%.1f" % (
start_loc.lat, start_loc.lng, start_loc.alt, start_loc.heading)])
self.reboot_sitl()
self.change_mode("TAKEOFF")
# waiting for the EKF to be happy won't work
self.delay_sim_time(20)
self.arm_vehicle()
target_alt = self.get_parameter("TKOFF_ALT")
self.wait_altitude(target_alt-5, target_alt, relative=True)
# Wait a bit for the Takeoff altitude to settle.
self.delay_sim_time(5)
bearing_margin = 35
loc = self.mav.location()
bearing_from_home = self.get_bearing(start_loc, loc)
if bearing_from_home < 0:
bearing_from_home += 360
if abs(bearing_from_home - start_loc.heading) > bearing_margin:
raise NotAchievedException(f"Did not takeoff in the right direction {bearing_from_home}")
self.fly_home_land_and_disarm()
def TakeoffGround(self): def TakeoffGround(self):
'''Test a rolling TAKEOFF.''' '''Test a rolling TAKEOFF.'''
@ -6525,6 +6560,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.TakeoffTakeoff2, self.TakeoffTakeoff2,
self.TakeoffTakeoff3, self.TakeoffTakeoff3,
self.TakeoffTakeoff4, self.TakeoffTakeoff4,
self.TakeoffTakeoff5,
self.TakeoffGround, self.TakeoffGround,
self.TakeoffIdleThrottle, self.TakeoffIdleThrottle,
self.TakeoffBadLevelOff, self.TakeoffBadLevelOff,