Skip to content

Commit fb1ac6b

Browse files
committed
autotest: add test for simulated Copter clamp
1 parent e3c2a45 commit fb1ac6b

File tree

2 files changed

+96
-13
lines changed

2 files changed

+96
-13
lines changed

Tools/autotest/arducopter.py

Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11428,6 +11428,78 @@ def GuidedWeatherVane(self):
1142811428
self.wait_heading(90, timeout=60, minimum_duration=10)
1142911429
self.do_RTL()
1143011430

11431+
def Clamp(self):
11432+
'''test Copter docking clamp'''
11433+
clamp_ch = 11
11434+
self.set_parameters({
11435+
"SIM_CLAMP_CH": clamp_ch,
11436+
})
11437+
11438+
self.takeoff(1, mode='LOITER')
11439+
11440+
self.context_push()
11441+
self.context_collect('STATUSTEXT')
11442+
self.progress("Ensure can't take off with clamp in place")
11443+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000)
11444+
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
11445+
self.arm_vehicle()
11446+
self.set_rc(3, 2000)
11447+
self.wait_altitude(0, 5, minimum_duration=5, relative=True)
11448+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000)
11449+
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)
11450+
self.wait_altitude(5, 5000, minimum_duration=1, relative=True)
11451+
self.do_RTL()
11452+
self.set_rc(3, 1000)
11453+
self.change_mode('LOITER')
11454+
self.context_pop()
11455+
11456+
self.progress("Same again for repeatability")
11457+
self.context_push()
11458+
self.context_collect('STATUSTEXT')
11459+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000)
11460+
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
11461+
self.arm_vehicle()
11462+
self.set_rc(3, 2000)
11463+
self.wait_altitude(0, 1, minimum_duration=5, relative=True)
11464+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000)
11465+
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)
11466+
self.wait_altitude(5, 5000, minimum_duration=1, relative=True)
11467+
self.do_RTL()
11468+
self.set_rc(3, 1000)
11469+
self.change_mode('LOITER')
11470+
self.context_pop()
11471+
11472+
here = self.mav.location()
11473+
loc = self.offset_location_ne(here, 10, 0)
11474+
self.takeoff(5, mode='GUIDED')
11475+
self.do_reposition(loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL)
11476+
self.wait_location(loc, timeout=120)
11477+
self.land_and_disarm()
11478+
11479+
# explicitly set home so we RTL to the right spot
11480+
self.set_home(here)
11481+
11482+
self.context_push()
11483+
self.context_collect('STATUSTEXT')
11484+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000)
11485+
self.wait_statustext("SITL: Clamp: missed vehicle", check_context=True)
11486+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=1000)
11487+
self.context_pop()
11488+
11489+
self.takeoff(5, mode='GUIDED')
11490+
self.do_RTL()
11491+
11492+
self.takeoff(5, mode='GUIDED')
11493+
self.land_and_disarm()
11494+
11495+
self.context_push()
11496+
self.context_collect('STATUSTEXT')
11497+
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=11, p2=2000)
11498+
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
11499+
self.context_pop()
11500+
11501+
self.reboot_sitl() # because we set home
11502+
1143111503
def tests2b(self): # this block currently around 9.5mins here
1143211504
'''return list of all tests'''
1143311505
ret = ([
@@ -11517,6 +11589,7 @@ def tests2b(self): # this block currently around 9.5mins here
1151711589
self.FarOrigin,
1151811590
self.GuidedForceArm,
1151911591
self.GuidedWeatherVane
11592+
self.Clamp,
1152011593
])
1152111594
return ret
1152211595

Tools/autotest/vehicle_test_suite.py

Lines changed: 23 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -6225,19 +6225,20 @@ def run_cmd_int(self,
62256225
command_name = mavutil.mavlink.enums["MAV_CMD"][command].name
62266226
except KeyError:
62276227
command_name = "UNKNOWNu"
6228-
self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f)" %
6229-
(
6230-
target_sysid,
6231-
target_compid,
6232-
command_name,
6233-
command,
6234-
p1,
6235-
p2,
6236-
p3,
6237-
p4,
6238-
x,
6239-
y,
6240-
z))
6228+
self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f f=%u)" % (
6229+
target_sysid,
6230+
target_compid,
6231+
command_name,
6232+
command,
6233+
p1,
6234+
p2,
6235+
p3,
6236+
p4,
6237+
x,
6238+
y,
6239+
z,
6240+
frame
6241+
))
62416242
mav.mav.command_int_send(target_sysid,
62426243
target_compid,
62436244
frame,
@@ -8508,6 +8509,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=
85088509
self.reset_SITL_commandline()
85098510
else:
85108511
self.progress("Force-rebooting SITL")
8512+
self.zero_throttle()
85118513
self.reboot_sitl() # that'll learn it
85128514
passed = False
85138515
elif ardupilot_alive and not passed: # implicit reboot after a failed test:
@@ -10833,6 +10835,14 @@ def GripperType(self, gripper_type):
1083310835
self.context_pop()
1083410836
self.reboot_sitl()
1083510837

10838+
def set_home(self, loc):
10839+
self.run_cmd(
10840+
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
10841+
p5=loc.lat,
10842+
p6=loc.lng,
10843+
p7=loc.alt,
10844+
)
10845+
1083610846
def TestLocalHomePosition(self):
1083710847
"""Test local home position is sent in HOME_POSITION message"""
1083810848
self.context_push()

0 commit comments

Comments
 (0)