Skip to content

Commit ddd3e93

Browse files
priseboroughtridge
authored andcommitted
Tools: Add test for quadplane forward motor use and pitch limiting
1 parent d53d512 commit ddd3e93

File tree

1 file changed

+35
-0
lines changed

1 file changed

+35
-0
lines changed

Tools/autotest/quadplane.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -745,6 +745,40 @@ def PilotYaw(self):
745745
self.set_rc(4, 1500)
746746
self.do_RTL()
747747

748+
def FwdThrInVTOL(self):
749+
'''test use of fwd motor throttle into wind'''
750+
self.set_parameters({"SIM_WIND_SPD": 25, # need very strong wind for this test
751+
"SIM_WIND_DIR": 360,
752+
"Q_WVANE_ENABLE": 1,
753+
"Q_WVANE_GAIN": 1,
754+
"STICK_MIXING": 0,
755+
"Q_FWD_THR_USE": 2,
756+
"SIM_ENGINE_FAIL": 2}) # we want to fail the forward thrust motor only
757+
758+
self.takeoff(10, mode="QLOITER")
759+
self.set_rc(2, 1000)
760+
self.delay_sim_time(10)
761+
# Check that it is using some forward throttle
762+
fwd_thr_pwm = self.get_servo_channel_value(3)
763+
if fwd_thr_pwm < 1150 :
764+
raise NotAchievedException("fwd motor pwm command low, want >= 1150 got %f" % (fwd_thr_pwm))
765+
# check that pitch is on limit
766+
m = self.mav.recv_match(type='ATTITUDE', blocking=True)
767+
pitch = math.degrees(m.pitch)
768+
if abs(pitch + 3.0) > 0.5 :
769+
raise NotAchievedException("pitch should be -3.0 +- 0.5 deg, got %f" % (pitch))
770+
self.set_rc(2, 1500)
771+
self.delay_sim_time(5)
772+
loc1 = self.mav.location()
773+
self.set_parameter("SIM_ENGINE_MUL", 0) # simulate a complete loss of forward motor thrust
774+
self.delay_sim_time(20)
775+
self.change_mode('QLAND')
776+
self.wait_disarmed(timeout=60)
777+
loc2 = self.mav.location()
778+
position_drift = self.get_distance(loc1, loc2)
779+
if position_drift > 5.0 :
780+
raise NotAchievedException("position drift high, want < 5.0 m got %f m" % (position_drift))
781+
748782
def Weathervane(self):
749783
'''test nose-into-wind functionality'''
750784
# We test nose into wind code paths and yaw direction in copter autotest,
@@ -1413,6 +1447,7 @@ def tests(self):
14131447

14141448
ret = super(AutoTestQuadPlane, self).tests()
14151449
ret.extend([
1450+
self.FwdThrInVTOL,
14161451
self.AirMode,
14171452
self.TestMotorMask,
14181453
self.PilotYaw,

0 commit comments

Comments
 (0)