@@ -10783,6 +10783,38 @@ def PILOT_THR_BHV(self):
10783
10783
10784
10784
self .wait_disarmed ()
10785
10785
10786
+ def MountRetractOnLanding (self ):
10787
+ '''test mount retracts on landing when asked to'''
10788
+ self .context_push ()
10789
+ self .setup_servo_mount ()
10790
+ self .set_parameter ("MNT1_OPTIONS" , 2 )
10791
+ self .reboot_sitl () # to handle MNT_TYPE changing
10792
+
10793
+ self .takeoff (10 , mode = 'GUIDED' )
10794
+
10795
+ self .test_mount_pitch (0 , 1 , mavutil .mavlink .MAV_MOUNT_MODE_MAVLINK_TARGETING )
10796
+
10797
+ angle = - 10
10798
+ self .run_cmd_int (
10799
+ mavutil .mavlink .MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW ,
10800
+ p1 = angle , # pitch angle in degrees
10801
+ p2 = 0 , # yaw angle in degrees
10802
+ p3 = 0 , # pitch rate in degrees (NaN to ignore)
10803
+ p4 = 0 , # yaw rate in degrees (NaN to ignore)
10804
+ p5 = 0 , # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame)
10805
+ p6 = 0 , # unused
10806
+ p7 = 0 , # gimbal id
10807
+ )
10808
+ self .test_mount_pitch (angle , 1 , mavutil .mavlink .MAV_MOUNT_MODE_MAVLINK_TARGETING )
10809
+
10810
+ self .change_mode ('LAND' )
10811
+ self .test_mount_pitch (0 , 1 , mavutil .mavlink .MAV_MOUNT_MODE_RETRACT )
10812
+
10813
+ self .wait_disarmed ()
10814
+
10815
+ self .context_pop ()
10816
+ self .reboot_sitl ()
10817
+
10786
10818
def CameraLogMessages (self ):
10787
10819
'''ensure Camera log messages are good'''
10788
10820
self .set_parameter ("RC12_OPTION" , 9 ) # CameraTrigger
@@ -10898,6 +10930,7 @@ def tests2b(self): # this block currently around 9.5mins here
10898
10930
self .TerrainDBPreArm ,
10899
10931
self .ThrottleGainBoost ,
10900
10932
self .ScriptMountPOI ,
10933
+ self .MountRetractOnLanding ,
10901
10934
self .FlyMissionTwice ,
10902
10935
self .FlyMissionTwiceWithReset ,
10903
10936
self .MissionIndexValidity ,
0 commit comments