@@ -11428,6 +11428,78 @@ def GuidedWeatherVane(self):
11428
11428
self .wait_heading (90 , timeout = 60 , minimum_duration = 10 )
11429
11429
self .do_RTL ()
11430
11430
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
+
11431
11503
def tests2b (self ): # this block currently around 9.5mins here
11432
11504
'''return list of all tests'''
11433
11505
ret = ([
@@ -11517,6 +11589,7 @@ def tests2b(self): # this block currently around 9.5mins here
11517
11589
self .FarOrigin ,
11518
11590
self .GuidedForceArm ,
11519
11591
self .GuidedWeatherVane
11592
+ self .Clamp ,
11520
11593
])
11521
11594
return ret
11522
11595
0 commit comments