Skip to content

Commit

Permalink
autotest:add AUTOLAND mode test
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Dec 2, 2024
1 parent ec29a9d commit 12c54e5
Showing 1 changed file with 15 additions and 2 deletions.
17 changes: 15 additions & 2 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -4200,6 +4200,19 @@ def FlyEachFrame(self):
self.fly_mission(mission_file, strict=False, quadplane=quadplane, mission_timeout=400.0)
self.wait_disarmed()

def AutoLandMode(self):
'''Test AUTOLAND mode'''
self.customise_SITL_commandline(["--home", "-35.362938,149.165085,585,173"])
self.change_mode("TAKEOFF")
self.wait_ready_to_arm()
self.arm_vehicle()
self.wait_text("Takeoff initial direction")
self.wait_altitude(15, 20, relative=True)
self.change_mode(26)
self.wait_disarmed(120)
self.progress("Check the landed heading matches takeoff")
self.wait_heading(173, accuracy=10, timeout=1)

def RCDisableAirspeedUse(self):
'''Test RC DisableAirspeedUse option'''
self.set_parameter("RC9_OPTION", 106)
Expand Down Expand Up @@ -4430,7 +4443,6 @@ def TakeoffAuto2(self):
- TKOFF_OPTIONS[0]=0
- TKOFF_THR_MAX > THR_MAX
'''

self.customise_SITL_commandline(
[],
model='plane-catapult',
Expand Down Expand Up @@ -4567,7 +4579,7 @@ def TakeoffAuto4(self):
self.set_servo(7, 2000)

# Ensure that TKOFF_THR_MAX_T is respected.
self.delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1)
delay_sim_time(self.get_parameter("TKOFF_THR_MAX_T")-1)
target_throttle = 1000+10*(self.get_parameter("TKOFF_THR_MAX"))
self.assert_servo_channel_range(3, target_throttle-10, target_throttle+10)

Expand Down Expand Up @@ -6404,6 +6416,7 @@ def tests1b(self):
self.MAV_CMD_DO_AUX_FUNCTION,
self.SmartBattery,
self.FlyEachFrame,
self.AutoLandMode,
self.RCDisableAirspeedUse,
self.AHRS_ORIENTATION,
self.AHRSTrim,
Expand Down

0 comments on commit 12c54e5

Please sign in to comment.