Skip to content

Commit

Permalink
autotest: add test for automated docking clamp release
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Jun 20, 2024
1 parent 5287829 commit 02655fe
Showing 1 changed file with 67 additions and 0 deletions.
67 changes: 67 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11514,6 +11514,72 @@ def Clamp(self):

self.reboot_sitl() # because we set home

def TakeoffClampRelease(self):
'''check automated docking clamp release'''
self.context_push()
clamp_ch = 11
rc_clamp_ch = 9
self.set_parameters({
"SIM_CLAMP_CH": clamp_ch,
f"SERVO{clamp_ch}_FUNCTION": 156,
f"RC{rc_clamp_ch}_OPTION": 179,
})
self.reboot_sitl()
self.context_collect('STATUSTEXT')

self.start_subtest("grab with aux function")
self.run_auxfunc(179, 2)
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
self.run_auxfunc(179, 0)
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)

self.start_subtest("grab with RC")
self.set_rc(rc_clamp_ch, 2000)
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
self.set_rc(rc_clamp_ch, 1000)
self.wait_statustext("SITL: Clamp: released vehicle", check_context=True)

self.start_subtest("should not be able to take off without the option bit set")
self.run_auxfunc(179, 2)
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
self.wait_ready_to_arm()
self.arm_vehicle()
self.change_mode('STABILIZE')
self.set_rc(3, 2000)
self.wait_altitude(0, 5, minimum_duration=5, relative=True)
self.zero_throttle()
self.delay_sim_time(1)
self.disarm_vehicle()

self.progress("Setting flight options bit")
current_value = int(self.get_parameter("FLIGHT_OPTIONS"))
current_value |= 8 # enable clamp release
self.set_parameter("FLIGHT_OPTIONS", current_value)

self.start_subtest("should be able to take off with the option bit set")
self.takeoff(10, mode='GUIDED')
self.do_RTL()
self.zero_throttle()

self.start_subtest("should be able to take off in auto mode with option bit set")
self.run_auxfunc(179, 0)
self.run_auxfunc(179, 2)
self.wait_statustext("SITL: Clamp: grabbed vehicle", check_context=True)
self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
])
self.set_parameters({
"AUTO_OPTIONS": 3,
})
self.change_mode('AUTO')
self.arm_vehicle()
self.wait_altitude(0, 5, minimum_duration=5, relative=True)
self.wait_disarmed()

self.context_pop()
self.reboot_sitl()

def GripperReleaseOnThrustLoss(self):
'''tests that gripper is released on thrust loss if option set'''

Expand Down Expand Up @@ -11625,6 +11691,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.GuidedWeatherVane,
self.Clamp,
self.GripperReleaseOnThrustLoss,
self.TakeoffClampRelease,
])
return ret

Expand Down

0 comments on commit 02655fe

Please sign in to comment.