auototest: fail test if pymavlink too old
This commit is contained in:
parent
085a10a3a1
commit
d182baa6b8
@ -20,6 +20,7 @@ from common import AutoTestTimeoutException
|
||||
from common import NotAchievedException
|
||||
from common import PreconditionFailedException
|
||||
from common import WaitModeTimeout
|
||||
from common import OldpymavlinkException
|
||||
from pymavlink.rotmat import Vector3
|
||||
from pysim import vehicleinfo
|
||||
|
||||
@ -582,7 +583,7 @@ class AutoTestPlane(AutoTest):
|
||||
def ExternalPositionEstimate(self):
|
||||
'''Test mavlink EXTERNAL_POSITION_ESTIMATE command'''
|
||||
if not hasattr(mavutil.mavlink, 'MAV_CMD_EXTERNAL_POSITION_ESTIMATE'):
|
||||
return
|
||||
raise OldpymavlinkException("pymavlink too old; upgrade pymavlink to get MAV_CMD_EXTERNAL_POSITION_ESTIMATE") # noqa
|
||||
self.change_mode("TAKEOFF")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
@ -168,6 +168,11 @@ class NotAchievedException(ErrorException):
|
||||
pass
|
||||
|
||||
|
||||
class OldpymavlinkException(ErrorException):
|
||||
"""Thrown when a new feature is required from pymavlink"""
|
||||
pass
|
||||
|
||||
|
||||
class YawSpeedNotAchievedException(NotAchievedException):
|
||||
"""Thrown when fails to achieve given yaw speed."""
|
||||
pass
|
||||
|
Loading…
Reference in New Issue
Block a user