Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add test for moving from guided to loiter #26784

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 16 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -10828,6 +10828,21 @@ def CameraLogMessages(self):
if abs(got - want) > 1:
raise NotAchievedException(f"Incorrect relalt {want=} {got=}")

def LoiterToGuidedHomeVSOrigin(self):
'''test moving from guided to loiter mode when home is a different alt
to origin'''
self.set_parameters({
"TERRAIN_ENABLE": 1,
"SIM_TERRAIN": 1,
})
self.takeoff(10, mode='GUIDED')
here = self.mav.location()
self.set_home(here)
self.change_mode('LOITER')
self.wait_altitude(here.alt-1, here.alt+1, minimum_duration=10)
self.disarm_vehicle(force=True)
self.reboot_sitl() # to "unstick" home

def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
Expand Down Expand Up @@ -10906,6 +10921,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.PILOT_THR_BHV,
self.GPSForYawCompassLearn,
self.CameraLogMessages,
self.LoiterToGuidedHomeVSOrigin,
])
return ret

Expand Down
9 changes: 9 additions & 0 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -8993,6 +8993,15 @@ def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):
self.progress("GroundSpeed OK (got=%f) (want=%f)" %
(m.groundspeed, want))

def set_home(self, loc):
'''set home to supplied loc'''
self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
p5=int(loc.lat*1e7),
p6=int(loc.lng*1e7),
p7=loc.alt,
)

def SetHome(self):
'''Setting and fetching of home'''
if self.is_tracker():
Expand Down
Loading