autotest: Enabled/edited old test and added new test on home alt reset

This commit is contained in:
George Zogopoulos 2024-11-27 12:25:12 +01:00 committed by Peter Barker
parent b0490d6400
commit 7e3ae6c6e6
1 changed files with 26 additions and 5 deletions

View File

@ -6338,14 +6338,18 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
def SetHomeAltChange(self): def SetHomeAltChange(self):
'''check modes retain altitude when home alt changed''' '''check modes retain altitude when home alt changed'''
for mode in 'FBWB', 'CRUISE', 'LOITER': for mode in 'FBWB', 'CRUISE', 'LOITER':
self.set_rc(3, 1000)
self.wait_ready_to_arm() self.wait_ready_to_arm()
home = self.home_position_as_mav_location() home = self.home_position_as_mav_location()
self.takeoff(20) target_alt = 20
higher_home = home self.takeoff(target_alt, mode="TAKEOFF")
self.delay_sim_time(20) # Give some time to altitude to stabilize.
self.set_rc(3, 1500)
self.change_mode(mode)
higher_home = copy.copy(home)
higher_home.alt += 40 higher_home.alt += 40
self.set_home(higher_home) self.set_home(higher_home)
self.change_mode(mode) self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=10, timeout=11)
self.wait_altitude(15, 25, relative=True, minimum_duration=10)
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
self.reboot_sitl() self.reboot_sitl()
@ -6381,6 +6385,23 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
self.reboot_sitl() self.reboot_sitl()
def SetHomeAltChange3(self):
'''same as SetHomeAltChange, but the home alt change occurs during TECS operation'''
self.wait_ready_to_arm()
home = self.home_position_as_mav_location()
target_alt = 20
self.takeoff(target_alt, mode="TAKEOFF")
self.change_mode("LOITER")
self.delay_sim_time(20) # Let the plane settle.
higher_home = copy.copy(home)
higher_home.alt += 40
self.set_home(higher_home)
self.wait_altitude(home.alt+target_alt-5, home.alt+target_alt+5, relative=False, minimum_duration=10, timeout=10.1)
self.disarm_vehicle(force=True)
self.reboot_sitl()
def ForceArm(self): def ForceArm(self):
'''check force-arming functionality''' '''check force-arming functionality'''
self.set_parameter("SIM_GPS1_ENABLE", 0) self.set_parameter("SIM_GPS1_ENABLE", 0)
@ -6653,6 +6674,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.GPSPreArms, self.GPSPreArms,
self.SetHomeAltChange, self.SetHomeAltChange,
self.SetHomeAltChange2, self.SetHomeAltChange2,
self.SetHomeAltChange3,
self.ForceArm, self.ForceArm,
self.MAV_CMD_EXTERNAL_WIND_ESTIMATE, self.MAV_CMD_EXTERNAL_WIND_ESTIMATE,
self.GliderPullup, self.GliderPullup,
@ -6664,7 +6686,6 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
"LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", "LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054",
"InteractTest": "requires user interaction", "InteractTest": "requires user interaction",
"ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass", "ClimbThrottleSaturation": "requires https://github.com/ArduPilot/ardupilot/pull/27106 to pass",
"SetHomeAltChange": "https://github.com/ArduPilot/ardupilot/issues/5672",
} }