Skip to content

Commit a354a79

Browse files
committed
autotest: add test for TECS overspeed
1 parent 24e54da commit a354a79

File tree

1 file changed

+30
-0
lines changed

1 file changed

+30
-0
lines changed

Tools/autotest/arduplane.py

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5356,6 +5356,35 @@ def ClimbThrottleSaturation(self):
53565356
self.disarm_vehicle(force=True)
53575357
self.reboot_sitl()
53585358

5359+
def TECSDescendPitch(self):
5360+
'''check TECS doesn't over-speed when descending'''
5361+
self.set_parameters({
5362+
"TECS_SINK_MAX": 300,
5363+
})
5364+
5365+
airspeed_max = 10
5366+
self.set_parameter('AIRSPEED_MAX', airspeed_max)
5367+
5368+
self.takeoff(400, mode='TAKEOFF', timeout=240)
5369+
5370+
loc = self.mav.location()
5371+
new_alt = 10
5372+
self.run_cmd_int(
5373+
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
5374+
p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
5375+
p5=int(loc.lat * 1e7),
5376+
p6=int(loc.lng * 1e7),
5377+
p7=new_alt, # alt
5378+
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5379+
)
5380+
5381+
self.wait_message_field_values('VFR_HUD', {
5382+
"airspeed": airspeed_max,
5383+
}, minimum_duration=30, timeout=90, epsilon=1)
5384+
5385+
self.disarm_vehicle(force=True)
5386+
self.reboot_sitl()
5387+
53595388
def tests(self):
53605389
'''return list of all tests'''
53615390
ret = super(AutoTestPlane, self).tests()
@@ -5466,6 +5495,7 @@ def tests(self):
54665495
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
54675496
self.MinThrottle,
54685497
self.ClimbThrottleSaturation,
5498+
self.TECSDescendPitch,
54695499
])
54705500
return ret
54715501

0 commit comments

Comments
 (0)