autotest: Copter: add test for DO_CHANGE_SPEED in guided mode

This commit is contained in:
Peter Barker 2023-09-20 10:10:16 +10:00 committed by Peter Barker
parent c61022f596
commit 613524d7d5

View File

@ -10187,6 +10187,44 @@ class AutoTestCopter(AutoTest):
self.change_mode('RTL')
self.wait_disarmed()
def DO_CHANGE_SPEED_in_guided(self):
'''test Copter DO_CHANGE_SPEED handling in guided mode'''
self.takeoff(20, mode='GUIDED')
loc = self.mav.location()
new_loc = self.mav.location()
new_loc_offset_n = 2000
new_loc_offset_e = 0
self.location_offset_ne(new_loc, new_loc_offset_n, new_loc_offset_e)
# for run_cmd we fly away from home
for (tloc, command) in (new_loc, self.run_cmd), (loc, self.run_cmd_int):
self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
p1=-1, # "default"
p2=0, # flags; none supplied here
p3=0, # loiter radius for planes, zero ignored
p4=float("nan"), # nan means do whatever you want to do
p5=int(tloc.lat * 1e7),
p6=int(tloc.lng * 1e7),
p7=tloc.alt,
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
)
for speed in [2, 10, 4]:
command(
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
p1=1, # groundspeed,
p2=speed,
p3=-1, # throttle, -1 is no-change
p4=0, # absolute value, not relative
)
self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=2)
# we've made random changes to vehicle guided speeds above;
# reboot vehicle to reset those:
self.disarm_vehicle(force=True)
self.reboot_sitl()
def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
@ -10246,6 +10284,7 @@ class AutoTestCopter(AutoTest):
self.AHRSTrimLand,
self.GuidedYawRate,
self.NoArmWithoutMissionItems,
self.DO_CHANGE_SPEED_in_guided,
self.RPLidarA1,
self.RPLidarA2,
self.SafetySwitch,