autotest: add test for TECS overspeed
This commit is contained in:
parent
613b835d67
commit
0c9142ff1b
@ -6316,6 +6316,34 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.context_pop()
|
||||
self.reboot_sitl()
|
||||
|
||||
def TECSDescendPitch(self):
|
||||
'''check TECS doesn't over-speed when descending'''
|
||||
self.set_parameters({
|
||||
"TECS_SINK_MAX": 300,
|
||||
})
|
||||
|
||||
airspeed_max = 10
|
||||
self.set_parameter('AIRSPEED_MAX', airspeed_max)
|
||||
|
||||
self.takeoff(400, mode='TAKEOFF', timeout=240)
|
||||
|
||||
loc = self.mav.location()
|
||||
new_alt = 10
|
||||
self.run_cmd_int(
|
||||
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
|
||||
p2=mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
|
||||
p5=int(loc.lat * 1e7),
|
||||
p6=int(loc.lng * 1e7),
|
||||
p7=new_alt, # alt
|
||||
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
|
||||
)
|
||||
|
||||
self.wait_message_field_values('VFR_HUD', {
|
||||
"airspeed": airspeed_max,
|
||||
}, minimum_duration=30, timeout=90, epsilon=1)
|
||||
|
||||
self.disarm_vehicle(force=True)
|
||||
|
||||
def GPSPreArms(self):
|
||||
'''ensure GPS prearm checks work'''
|
||||
self.wait_ready_to_arm()
|
||||
@ -6573,6 +6601,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
self.FRSkyPassThroughSensorIDs,
|
||||
self.FRSkyMAVlite,
|
||||
self.FRSkyD,
|
||||
self.TECSDescendPitch,
|
||||
self.LTM,
|
||||
self.DEVO,
|
||||
self.AdvancedFailsafe,
|
||||
|
Loading…
Reference in New Issue
Block a user