@@ -10843,6 +10843,27 @@ def LoiterToGuidedHomeVSOrigin(self):
10843
10843
self .disarm_vehicle (force = True )
10844
10844
self .reboot_sitl () # to "unstick" home
10845
10845
10846
+ def GuidedModeThrust (self ):
10847
+ '''test handling of option-bit-3, where mavlink commands are
10848
+ intrepreted as thrust not climb rate'''
10849
+ self .set_parameter ('GUID_OPTIONS' , 8 )
10850
+ self .change_mode ('GUIDED' )
10851
+ self .wait_ready_to_arm ()
10852
+ self .arm_vehicle ()
10853
+ self .mav .mav .set_attitude_target_send (
10854
+ 0 , # time_boot_ms
10855
+ 1 , # target sysid
10856
+ 1 , # target compid
10857
+ 0 , # bitmask of things to ignore
10858
+ mavextra .euler_to_quat ([0 , 0 , 0 ]), # att
10859
+ 0 , # roll rate (rad/s)
10860
+ 0 , # pitch rate (rad/s)
10861
+ 0 , # yaw rate (rad/s)
10862
+ 0.5
10863
+ ) # thrust, 0 to 1
10864
+ self .wait_altitude (0.5 , 100 , relative = True , timeout = 10 )
10865
+ self .do_RTL ()
10866
+
10846
10867
def tests2b (self ): # this block currently around 9.5mins here
10847
10868
'''return list of all tests'''
10848
10869
ret = ([
@@ -10922,6 +10943,7 @@ def tests2b(self): # this block currently around 9.5mins here
10922
10943
self .GPSForYawCompassLearn ,
10923
10944
self .CameraLogMessages ,
10924
10945
self .LoiterToGuidedHomeVSOrigin ,
10946
+ self .GuidedModeThrust ,
10925
10947
])
10926
10948
return ret
10927
10949
@@ -10952,6 +10974,7 @@ def disabled_tests(self):
10952
10974
"GroundEffectCompensation_touchDownExpected" : "Flapping" ,
10953
10975
"FlyMissionTwice" : "See https://github.com/ArduPilot/ardupilot/pull/18561" ,
10954
10976
"GPSForYawCompassLearn" : "Vehicle currently crashed in spectacular fashion" ,
10977
+ "GuidedModeThrust" : "land detector raises internal error as we're not saying we're about to take off but just did" ,
10955
10978
}
10956
10979
10957
10980
0 commit comments