Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/autotest/vehicle_test_suite.py
Views: 1798
'''1Common base class for each of the autotest suites23AP_FLAKE8_CLEAN45'''6from __future__ import print_function78import abc9import copy10import errno11import glob12import math13import os14import re15import shutil16import signal17import sys18import time19import traceback20from datetime import datetime21from typing import List22from typing import Tuple23from typing import Dict24import importlib.util2526import pexpect27import fnmatch28import operator29import numpy30import socket31import struct32import random33import tempfile34import threading35import enum36from inspect import currentframe, getframeinfo37from pathlib import Path3839from MAVProxy.modules.lib import mp_util40from MAVProxy.modules.lib import mp_elevation4142from pymavlink import mavparm43from pymavlink import mavwp, mavutil, DFReader44from pymavlink import mavextra45from pymavlink.rotmat import Vector346from pymavlink import quaternion47from pymavlink.generator import mavgen4849from pysim import util, vehicleinfo5051try:52import queue as Queue53except ImportError:54import Queue555657# Enumeration convenience class for mavlink POSITION_TARGET_TYPEMASK58class MAV_POS_TARGET_TYPE_MASK(enum.IntEnum):59POS_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |60mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |61mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE)62VEL_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |63mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |64mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE)65ACC_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |66mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |67mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE)68FORCE_SET = mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET69YAW_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE70YAW_RATE_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE71POS_ONLY = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE72LAST_BYTE = 0xF000737475MAV_FRAMES_TO_TEST = [76mavutil.mavlink.MAV_FRAME_GLOBAL,77mavutil.mavlink.MAV_FRAME_GLOBAL_INT,78mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,79mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,80mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,81mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT82]8384# get location of scripts85testdir = os.path.dirname(os.path.realpath(__file__))8687# Check python version for abstract base class88if sys.version_info[0] >= 3 and sys.version_info[1] >= 4:89ABC = abc.ABC90else:91ABC = abc.ABCMeta('ABC', (), {})9293if sys.version_info[0] >= 3:94import io as StringIO # srsly, we just did that.95else:96import StringIO9798try:99from itertools import izip as zip100except ImportError:101# probably python2102pass103104105class ErrorException(Exception):106"""Base class for other exceptions"""107pass108109110class AutoTestTimeoutException(ErrorException):111pass112113114if sys.version_info[0] < 3:115ConnectionResetError = AutoTestTimeoutException116117118class WaitModeTimeout(AutoTestTimeoutException):119"""Thrown when fails to achieve given mode change."""120pass121122123class WaitAltitudeTimout(AutoTestTimeoutException):124"""Thrown when fails to achieve given altitude range."""125pass126127128class WaitGroundSpeedTimeout(AutoTestTimeoutException):129"""Thrown when fails to achieve given ground speed range."""130pass131132133class WaitRollTimeout(AutoTestTimeoutException):134"""Thrown when fails to achieve given roll in degrees."""135pass136137138class WaitPitchTimeout(AutoTestTimeoutException):139"""Thrown when fails to achieve given pitch in degrees."""140pass141142143class WaitHeadingTimeout(AutoTestTimeoutException):144"""Thrown when fails to achieve given heading."""145pass146147148class WaitDistanceTimeout(AutoTestTimeoutException):149"""Thrown when fails to attain distance"""150pass151152153class WaitLocationTimeout(AutoTestTimeoutException):154"""Thrown when fails to attain location"""155pass156157158class WaitWaypointTimeout(AutoTestTimeoutException):159"""Thrown when fails to attain waypoint ranges"""160pass161162163class SetRCTimeout(AutoTestTimeoutException):164"""Thrown when fails to send RC commands"""165pass166167168class MsgRcvTimeoutException(AutoTestTimeoutException):169"""Thrown when fails to receive an expected message"""170pass171172173class NotAchievedException(ErrorException):174"""Thrown when fails to achieve a goal"""175pass176177178class OldpymavlinkException(ErrorException):179"""Thrown when a new feature is required from pymavlink"""180pass181182183class YawSpeedNotAchievedException(NotAchievedException):184"""Thrown when fails to achieve given yaw speed."""185pass186187188class SpeedVectorNotAchievedException(NotAchievedException):189"""Thrown when fails to achieve given speed vector."""190pass191192193class PreconditionFailedException(ErrorException):194"""Thrown when a precondition for a test is not met"""195pass196197198class ArmedAtEndOfTestException(ErrorException):199"""Created when test left vehicle armed"""200pass201202203class Context(object):204def __init__(self):205self.parameters = []206self.sitl_commandline_customised = False207self.reboot_sitl_was_done = False208self.message_hooks = []209self.collections = {}210self.heartbeat_interval_ms = 1000211self.original_heartbeat_interval_ms = None212self.installed_scripts = []213self.installed_modules = []214self.overridden_message_rates = {}215216217# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python218class TeeBoth(object):219def __init__(self, name, mode, mavproxy_logfile, suppress_stdout=False):220self.suppress_stdout = suppress_stdout221self.file = open(name, mode)222self.stdout = sys.stdout223self.stderr = sys.stderr224self.mavproxy_logfile = mavproxy_logfile225self.mavproxy_logfile.set_fh(self)226sys.stdout = self227sys.stderr = self228229def close(self):230sys.stdout = self.stdout231sys.stderr = self.stderr232self.mavproxy_logfile.set_fh(None)233self.mavproxy_logfile = None234self.file.close()235self.file = None236237def write(self, data):238if isinstance(data, bytes):239data = data.decode('ascii')240self.file.write(data)241if not self.suppress_stdout:242self.stdout.write(data)243244def flush(self):245self.file.flush()246247248class MAVProxyLogFile(object):249def __init__(self):250self.fh = None251252def close(self):253pass254255def set_fh(self, fh):256self.fh = fh257258def write(self, data):259if self.fh is not None:260self.fh.write(data)261else:262sys.stdout.write(data)263264def flush(self):265if self.fh is not None:266self.fh.flush()267else:268sys.stdout.flush()269270271class Telem(object):272def __init__(self, destination_address, progress_function=None, verbose=False):273self.destination_address = destination_address274self.progress_function = progress_function275self.verbose = verbose276277self.buffer = bytes()278self.connected = False279self.port = None280self.progress_log = ""281282def progress(self, message):283message = "%s: %s" % (self.progress_tag(), message)284if self.progress_function is not None:285self.progress_function(message)286return287if not self.verbose:288self.progress_log += message289return290print(message)291292def connect(self):293try:294self.connected = False295self.progress("Connecting to (%s:%u)" % self.destination_address)296if self.port is not None:297try:298self.port.close() # might be reopening299except Exception:300pass301self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)302self.port.connect(self.destination_address)303self.port.setblocking(False)304self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)305self.connected = True306self.progress("Connected")307except IOError as e:308self.progress("Failed to connect: %s" % str(e))309time.sleep(0.5)310return False311return True312313def do_read(self):314try:315data = self.port.recv(1024)316except socket.error as e:317if e.errno not in [errno.EAGAIN, errno.EWOULDBLOCK]:318self.progress("Exception: %s" % str(e))319self.connected = False320return bytes()321if len(data) == 0:322self.progress("EOF")323self.connected = False324return bytes()325# self.progress("Read %u bytes" % len(data))326return data327328def do_write(self, some_bytes):329try:330written = self.port.send(some_bytes)331except socket.error as e:332if e.errno in [errno.EAGAIN, errno.EWOULDBLOCK]:333return 0334self.progress("Exception: %s" % str(e))335raise336if written != len(some_bytes):337raise ValueError("Short write")338339def update(self):340if not self.connected:341if not self.connect():342return343return self.update_read()344345346class IBusMessage(object):347def checksum_bytes(self, out):348checksum = 0xFFFF349for b in iter(out):350checksum -= b351return checksum352353354class IBusResponse(IBusMessage):355def __init__(self, some_bytes):356self.len = some_bytes[0]357checksum = self.checksum_bytes(some_bytes[:self.len-2])358if checksum >> 8 != some_bytes[self.len-1]:359raise ValueError("Checksum bad (-1)")360if checksum & 0xff != some_bytes[self.len-2]:361raise ValueError("Checksum bad (-2)")362self.address = some_bytes[1] & 0x0F363self.handle_payload_bytes(some_bytes[2:self.len-2])364365366class IBusResponse_DISCOVER(IBusResponse):367def handle_payload_bytes(self, payload_bytes):368if len(payload_bytes):369raise ValueError("Not expecting payload bytes (%u)" %370(len(payload_bytes), ))371372373class IBusResponse_GET_SENSOR_TYPE(IBusResponse):374def handle_payload_bytes(self, payload_bytes):375if len(payload_bytes) != 2:376raise ValueError("Expected 2 payload bytes")377self.sensor_type = payload_bytes[0]378self.sensor_length = payload_bytes[1]379380381class IBusResponse_GET_SENSOR_VALUE(IBusResponse):382def handle_payload_bytes(self, payload_bytes):383self.sensor_value = payload_bytes384385def get_sensor_value(self):386'''returns an integer based off content'''387ret = 0388for i in range(len(self.sensor_value)):389x = self.sensor_value[i]390if sys.version_info.major < 3:391x = ord(x)392ret = ret | (x << (i*8))393return ret394395396class IBusRequest(IBusMessage):397def __init__(self, command, address):398self.command = command399self.address = address400401def payload_bytes(self):402'''most requests don't have a payload'''403return bytearray()404405def for_wire(self):406out = bytearray()407payload_bytes = self.payload_bytes()408payload_length = len(payload_bytes)409length = 1 + 1 + payload_length + 2 # len+cmd|adr+payloadlen+cksum410format_string = '<BB' + ('B' * payload_length)411out.extend(struct.pack(format_string,412length,413(self.command << 4) | self.address,414*payload_bytes,415))416checksum = self.checksum_bytes(out)417out.extend(struct.pack("<BB", checksum & 0xff, checksum >> 8))418return out419420421class IBusRequest_DISCOVER(IBusRequest):422def __init__(self, address):423super(IBusRequest_DISCOVER, self).__init__(0x08, address)424425426class IBusRequest_GET_SENSOR_TYPE(IBusRequest):427def __init__(self, address):428super(IBusRequest_GET_SENSOR_TYPE, self).__init__(0x09, address)429430431class IBusRequest_GET_SENSOR_VALUE(IBusRequest):432def __init__(self, address):433super(IBusRequest_GET_SENSOR_VALUE, self).__init__(0x0A, address)434435436class IBus(Telem):437def __init__(self, destination_address):438super(IBus, self).__init__(destination_address)439440def progress_tag(self):441return "IBus"442443def packet_from_buffer(self, buffer):444t = buffer[1] >> 4445if sys.version_info.major < 3:446t = ord(t)447if t == 0x08:448return IBusResponse_DISCOVER(buffer)449if t == 0x09:450return IBusResponse_GET_SENSOR_TYPE(buffer)451if t == 0x0A:452return IBusResponse_GET_SENSOR_VALUE(buffer)453raise ValueError("Unknown response type (%u)" % t)454455def update_read(self):456self.buffer += self.do_read()457while len(self.buffer):458msglen = self.buffer[0]459if sys.version_info.major < 3:460msglen = ord(msglen)461if len(self.buffer) < msglen:462return463packet = self.packet_from_buffer(self.buffer[:msglen])464self.buffer = self.buffer[msglen:]465return packet466467468class WaitAndMaintain(object):469def __init__(self,470test_suite,471minimum_duration=None,472progress_print_interval=1,473timeout=30,474epsilon=None,475comparator=None,476):477self.test_suite = test_suite478self.minimum_duration = minimum_duration479self.achieving_duration_start = None480self.timeout = timeout481self.epsilon = epsilon482self.last_progress_print = 0483self.progress_print_interval = progress_print_interval484self.comparator = comparator485486def run(self):487self.announce_test_start()488489tstart = self.test_suite.get_sim_time_cached()490while True:491now = self.test_suite.get_sim_time_cached()492current_value = self.get_current_value()493if now - self.last_progress_print > self.progress_print_interval:494self.print_progress(now, current_value)495self.last_progress_print = now496497# check for timeout498if now - tstart > self.timeout:499self.print_failure_text(now, current_value)500raise self.timeoutexception()501502# handle the case where we are are achieving our value:503if self.validate_value(current_value):504if self.achieving_duration_start is None:505self.achieving_duration_start = now506if (self.minimum_duration is None or507now - self.achieving_duration_start > self.minimum_duration):508self.announce_success()509return True510continue511512# handle the case where we are not achieving our value:513self.achieving_duration_start = None514515def progress(self, text):516self.test_suite.progress(text)517518def announce_test_start(self):519self.progress(self.announce_start_text())520521def announce_success(self):522self.progress(self.success_text())523524def print_progress(self, now, value):525text = self.progress_text(value)526if self.achieving_duration_start is not None:527delta = now - self.achieving_duration_start528text += f" (maintain={delta:.1f}/{self.minimum_duration})"529self.progress(text)530531def print_failure_text(self, now, value):532'''optionally print a more detailed error string'''533pass534535def progress_text(self, value):536return f"want={self.get_target_value()} got={value}"537538def validate_value(self, value):539target_value = self.get_target_value()540if self.comparator is not None:541return self.comparator(value, target_value)542543if self.epsilon is not None:544return (abs(value - target_value) <= self.epsilon)545546return value == target_value547548def timeoutexception(self):549return AutoTestTimeoutException("Failed to attain or maintain value")550551def success_text(self):552return f"{type(self)} Success"553554555class WaitAndMaintainLocation(WaitAndMaintain):556def __init__(self, test_suite, target, accuracy=5, height_accuracy=1, **kwargs):557super(WaitAndMaintainLocation, self).__init__(test_suite, **kwargs)558self.target = target559self.height_accuracy = height_accuracy560self.accuracy = accuracy561562def announce_start_text(self):563t = self.target564if self.height_accuracy is not None:565return ("Waiting for distance to Location (%.4f, %.4f, %.2f) (h_err<%f, v_err<%.2f " %566(t.lat, t.lng, t.alt*0.01, self.accuracy, self.height_accuracy))567return ("Waiting for distance to Location (%.4f, %.4f) (h_err<%f" %568(t.lat, t.lng, self.accuracy))569570def get_target_value(self):571return self.loc572573def get_current_value(self):574return self.test_suite.mav.location()575576def horizontal_error(self, value):577return self.test_suite.get_distance(value, self.target)578579def vertical_error(self, value):580return math.fabs(value.alt*0.01 - self.target.alt*0.01)581582def validate_value(self, value):583if self.horizontal_error(value) > self.accuracy:584return False585586if self.height_accuracy is None:587return True588589if self.vertical_error(value) > self.height_accuracy:590return False591592return True593594def success_text(self):595return "Reached location"596597def timeoutexception(self):598return AutoTestTimeoutException("Failed to attain location")599600def progress_text(self, current_value):601if self.height_accuracy is not None:602return (f"Want=({self.target.lat:.7f},{self.target.lng:.7f},{self.target.alt:.2f}) Got=({current_value.lat:.7f},{current_value.lng:.7f},{current_value.alt:.2f}) dist={self.horizontal_error(current_value):.2f} vdist={self.vertical_error(current_value):.2f}") # noqa603604return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}")605606607class WaitAndMaintainEKFFlags(WaitAndMaintain):608'''Waits for EKF status flags to include required_flags and have609error_bits *not* set.'''610def __init__(self, test_suite, required_flags, error_bits, **kwargs):611super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs)612self.required_flags = required_flags613self.error_bits = error_bits614self.last_EKF_STATUS_REPORT = None615616def announce_start_text(self):617return f"Waiting for EKF value {self.required_flags}"618619def get_current_value(self):620self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10)621return self.last_EKF_STATUS_REPORT.flags622623def validate_value(self, value):624if value & self.error_bits:625return False626627if (value & self.required_flags) != self.required_flags:628return False629630return True631632def success_text(self):633return "EKF Flags OK"634635def timeoutexception(self):636self.progress("Last EKF status report:")637self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT))638639return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}")640641def progress_text(self, current_value):642error_bits = current_value & self.error_bits643return (f"Want={self.required_flags} got={current_value} errors={error_bits}")644645def ekf_flags_string(self, bits):646ret = []647for i in range(0, 16):648bit = 1 << i649try:650if not bits & bit:651continue652name = mavutil.mavlink.enums["ESTIMATOR_STATUS_FLAGS"][bit].name653trimmed_name = name.removeprefix("ESTIMATOR_")654ret.append(trimmed_name)655except KeyError:656ret.append(str(bit))657return "|".join(ret)658659def failure_text(self, now, current_value):660components = []661components.append(("want", self.ekf_flags_string(self.required_flags)))662663missing_bits = self.required_flags & ~current_value664if missing_bits:665components.append(("missing", self.ekf_flags_string(missing_bits)))666667error_bits = current_value & self.error_bits668if error_bits:669components.append(("errors", self.ekf_flags_string(error_bits)))670671return " ".join([f"{n}={v}" for (n, v) in components])672673def print_failure_text(self, now, current_value):674self.progress(self.failure_text(now, current_value))675676677class WaitAndMaintainArmed(WaitAndMaintain):678def get_current_value(self):679return self.test_suite.armed()680681def get_target_value(self):682return True683684def announce_start_text(self):685return "Ensuring vehicle remains armed"686687688class WaitAndMaintainServoChannelValue(WaitAndMaintain):689def __init__(self, test_suite, channel, value, **kwargs):690super(WaitAndMaintainServoChannelValue, self).__init__(test_suite, **kwargs)691self.channel = channel692self.value = value693694def announce_start_text(self):695str_operator = ""696if self.comparator == operator.lt:697str_operator = "less than "698elif self.comparator == operator.gt:699str_operator = "more than "700701return f"Waiting for SERVO_OUTPUT_RAW.servo{self.channel}_value value {str_operator}{self.value}"702703def get_target_value(self):704return self.value705706def get_current_value(self):707m = self.test_suite.assert_receive_message('SERVO_OUTPUT_RAW', timeout=10)708channel_field = "servo%u_raw" % self.channel709m_value = getattr(m, channel_field, None)710if m_value is None:711raise ValueError(f"message ({str(m)}) has no field {channel_field}")712713self.last_SERVO_OUTPUT_RAW = m714return m_value715716717class MSP_Generic(Telem):718def __init__(self, destination_address):719super(MSP_Generic, self).__init__(destination_address)720721self.callback = None722723self.STATE_IDLE = "IDLE"724self.STATE_WANT_HEADER_DOLLARS = "WANT_DOLLARS"725self.STATE_WANT_HEADER_M = "WANT_M"726self.STATE_WANT_HEADER_GT = "WANT_GT"727self.STATE_WANT_DATA_SIZE = "WANT_DATA_SIZE"728self.STATE_WANT_COMMAND = "WANT_COMMAND"729self.STATE_WANT_DATA = "WANT_DATA"730self.STATE_WANT_CHECKSUM = "WANT_CHECKSUM"731732self.state = self.STATE_IDLE733734def progress(self, message):735print("MSP: %s" % message)736737def set_state(self, state):738# self.progress("Moving to state (%s)" % state)739self.state = state740741def init_checksum(self, b):742self.checksum = 0743self.add_to_checksum(b)744745def add_to_checksum(self, b):746self.checksum ^= (b & 0xFF)747748def process_command(self, cmd, data):749if self.callback is not None:750self.callback(cmd, data)751else:752print("cmd=%s" % str(cmd))753754def update_read(self):755for byte in self.do_read():756if sys.version_info[0] < 3:757c = byte[0]758byte = ord(c)759else:760c = chr(byte)761# print("Got (0x%02x) (%s) (%s) state=%s" % (byte, chr(byte), str(type(byte)), self.state))762if self.state == self.STATE_IDLE:763# reset state764self.set_state(self.STATE_WANT_HEADER_DOLLARS)765# deliberate fallthrough right here766if self.state == self.STATE_WANT_HEADER_DOLLARS:767if c == '$':768self.set_state(self.STATE_WANT_HEADER_M)769continue770if self.state == self.STATE_WANT_HEADER_M:771if c != 'M':772raise Exception("Malformed packet")773self.set_state(self.STATE_WANT_HEADER_GT)774continue775if self.state == self.STATE_WANT_HEADER_GT:776if c != '>':777raise Exception("Malformed packet")778self.set_state(self.STATE_WANT_DATA_SIZE)779continue780if self.state == self.STATE_WANT_DATA_SIZE:781self.data_size = byte782self.set_state(self.STATE_WANT_COMMAND)783self.data = bytearray()784self.checksum = 0785self.add_to_checksum(byte)786continue787if self.state == self.STATE_WANT_COMMAND:788self.command = byte789self.add_to_checksum(byte)790if self.data_size != 0:791self.set_state(self.STATE_WANT_DATA)792else:793self.set_state(self.STATE_WANT_CHECKSUM)794continue795if self.state == self.STATE_WANT_DATA:796self.add_to_checksum(byte)797self.data.append(byte)798if len(self.data) == self.data_size:799self.set_state(self.STATE_WANT_CHECKSUM)800continue801if self.state == self.STATE_WANT_CHECKSUM:802if self.checksum != byte:803raise Exception("Checksum fail (want=0x%02x calced=0x%02x" %804(byte, self.checksum))805self.process_command(self.command, self.data)806self.set_state(self.STATE_IDLE)807808809class MSP_DJI(MSP_Generic):810FRAME_GPS_RAW = 106811FRAME_ATTITUDE = 108812813def __init__(self, destination_address):814super(MSP_DJI, self).__init__(destination_address)815self.callback = self.command_callback816self.frames = {}817818class Frame(object):819def __init__(self, data):820self.data = data821822def intn(self, offset, count):823ret = 0824for i in range(offset, offset+count):825ret = ret | (ord(self.data[i]) << ((i-offset)*8))826return ret827828def int32(self, offset):829t = struct.unpack("<i", self.data[offset:offset+4])830return t[0]831832def int16(self, offset):833t = struct.unpack("<h", self.data[offset:offset+2])834return t[0]835836class FrameATTITUDE(Frame):837def roll(self):838'''roll in degrees'''839return self.int16(0) * 10840841def pitch(self):842'''pitch in degrees'''843return self.int16(2) * 10844845def yaw(self):846'''yaw in degrees'''847return self.int16(4)848849class FrameGPS_RAW(Frame):850'''see gps_state_s'''851def fix_type(self):852return self.uint8(0)853854def num_sats(self):855return self.uint8(1)856857def lat(self):858return self.int32(2) / 1e7859860def lon(self):861return self.int32(6) / 1e7862863def LocationInt(self):864# other fields are available, I'm just lazy865return LocationInt(self.int32(2), self.int32(6), 0, 0)866867def command_callback(self, frametype, data):868# print("X: %s %s" % (str(frametype), str(data)))869if frametype == MSP_DJI.FRAME_ATTITUDE:870frame = MSP_DJI.FrameATTITUDE(data)871elif frametype == MSP_DJI.FRAME_GPS_RAW:872frame = MSP_DJI.FrameGPS_RAW(data)873else:874return875self.frames[frametype] = frame876877def get_frame(self, frametype):878return self.frames[frametype]879880881class LTM(Telem):882def __init__(self, destination_address):883super(LTM, self).__init__(destination_address)884885self.HEADER1 = 0x24886self.HEADER2 = 0x54887888self.FRAME_G = 0x47889self.FRAME_A = 0x41890self.FRAME_S = 0x53891892self.frame_lengths = {893self.FRAME_G: 18,894self.FRAME_A: 10,895self.FRAME_S: 11,896}897self.frame_lengths = {898self.FRAME_G: 18,899self.FRAME_A: 10,900self.FRAME_S: 11,901}902903self.data_by_id = {}904self.frames = {}905906def g(self):907return self.frames.get(self.FRAME_G, None)908909def a(self):910return self.frames.get(self.FRAME_A, None)911912def s(self):913return self.frames.get(self.FRAME_S, None)914915def progress_tag(self):916return "LTM"917918def handle_data(self, dataid, value):919self.progress("%u=%u" % (dataid, value))920self.data_by_id[dataid] = value921922def consume_frame(self):923b2 = self.buffer[2]924if sys.version_info.major < 3:925b2 = ord(b2)926frame_type = b2927frame_length = self.frame_lengths[frame_type]928# check frame CRC929crc = 0930count = 0931for c in self.buffer[3:frame_length-1]:932if sys.version_info.major < 3:933c = ord(c)934crc ^= c935count += 1936buffer_crc = self.buffer[frame_length-1]937if sys.version_info.major < 3:938buffer_crc = ord(buffer_crc)939if crc != buffer_crc:940raise NotAchievedException("Invalid checksum on frame type %s" % str(chr(frame_type)))941# self.progress("Received valid %s frame" % str(chr(frame_type)))942943class Frame(object):944def __init__(self, buffer):945self.buffer = buffer946947def intn(self, offset, count):948ret = 0949for i in range(offset, offset+count):950ret = ret | (ord(self.buffer[i]) << ((i-offset)*8))951return ret952953def int32(self, offset):954t = struct.unpack("<i", self.buffer[offset:offset+4])955return t[0]956# return self.intn(offset, 4)957958def int16(self, offset):959t = struct.unpack("<h", self.buffer[offset:offset+2])960return t[0]961# return self.intn(offset, 2)962963class FrameG(Frame):964def __init__(self, buffer):965super(FrameG, self,).__init__(buffer)966967def lat(self):968return self.int32(3)969970def lon(self):971return self.int32(7)972973def gndspeed(self):974ret = self.buffer[11]975if sys.version_info.major < 3:976ret = ord(ret)977return ret978979def alt(self):980return self.int32(12)981982def sats(self):983s = self.buffer[16]984if sys.version_info.major < 3:985s = ord(s)986return (s >> 2)987988def fix_type(self):989s = self.buffer[16]990if sys.version_info.major < 3:991s = ord(s)992return s & 0b11993994class FrameA(Frame):995def __init__(self, buffer):996super(FrameA, self,).__init__(buffer)997998def pitch(self):999return self.int16(3)10001001def roll(self):1002return self.int16(5)10031004def hdg(self):1005return self.int16(7)10061007class FrameS(Frame):1008def __init__(self, buffer):1009super(FrameS, self,).__init__(buffer)10101011if frame_type == self.FRAME_G:1012frame = FrameG(self.buffer[0:frame_length-1])1013elif frame_type == self.FRAME_A:1014frame = FrameA(self.buffer[0:frame_length-1])1015elif frame_type == self.FRAME_S:1016frame = FrameS(self.buffer[0:frame_length-1])1017else:1018raise NotAchievedException("Bad frame?!?!?!")1019self.buffer = self.buffer[frame_length:]1020self.frames[frame_type] = frame10211022def update_read(self):1023self.buffer += self.do_read()1024while len(self.buffer):1025if len(self.buffer) == 0:1026break1027b0 = self.buffer[0]1028if sys.version_info.major < 3:1029b0 = ord(b0)1030if b0 != self.HEADER1:1031self.bad_chars += 11032self.buffer = self.buffer[1:]1033continue1034b1 = self.buffer[1]1035if sys.version_info.major < 3:1036b1 = ord(b1)1037if b1 != self.HEADER2:1038self.bad_chars += 11039self.buffer = self.buffer[1:]1040continue1041b2 = self.buffer[2]1042if sys.version_info.major < 3:1043b2 = ord(b2)1044if b2 not in [self.FRAME_G, self.FRAME_A, self.FRAME_S]:1045self.bad_chars += 11046self.buffer = self.buffer[1:]1047continue1048frame_len = self.frame_lengths[b2]1049if len(self.buffer) < frame_len:1050continue1051self.consume_frame()10521053def get_data(self, dataid):1054try:1055return self.data_by_id[dataid]1056except KeyError:1057pass1058return None105910601061class CRSF(Telem):1062def __init__(self, destination_address):1063super(CRSF, self).__init__(destination_address)10641065self.dataid_vtx_frame = 01066self.dataid_vtx_telem = 11067self.dataid_vtx_unknown = 210681069self.data_id_map = {1070self.dataid_vtx_frame: bytearray([0xC8, 0x8, 0xF, 0xCE, 0x30, 0x8, 0x16, 0xE9, 0x0, 0x5F]),1071self.dataid_vtx_telem: bytearray([0xC8, 0x7, 0x10, 0xCE, 0xE, 0x16, 0x65, 0x0, 0x1B]),1072self.dataid_vtx_unknown: bytearray([0xC8, 0x9, 0x8, 0x0, 0x9E, 0x0, 0x0, 0x0, 0x0, 0x0, 0x95]),1073}10741075def write_data_id(self, dataid):1076self.do_write(self.data_id_map[dataid])10771078def progress_tag(self):1079return "CRSF"108010811082class DEVO(Telem):1083def __init__(self, destination_address):1084super(DEVO, self).__init__(destination_address)10851086self.HEADER = 0xAA1087self.frame_length = 2010881089# frame is 'None' until we receive a frame with VALID header and checksum1090self.frame = None1091self.bad_chars = 010921093def progress_tag(self):1094return "DEVO"10951096def consume_frame(self):1097# check frame checksum1098checksum = 01099for c in self.buffer[:self.frame_length-1]:1100if sys.version_info.major < 3:1101c = ord(c)1102checksum += c1103checksum &= 0xff # since we receive 8 bit checksum1104buffer_checksum = self.buffer[self.frame_length-1]1105if sys.version_info.major < 3:1106buffer_checksum = ord(buffer_checksum)1107if checksum != buffer_checksum:1108raise NotAchievedException("Invalid checksum")11091110class FRAME(object):1111def __init__(self, buffer):1112self.buffer = buffer11131114def int32(self, offset):1115t = struct.unpack("<i", self.buffer[offset:offset+4])1116return t[0]11171118def int16(self, offset):1119t = struct.unpack("<h", self.buffer[offset:offset+2])1120return t[0]11211122def lon(self):1123return self.int32(1)11241125def lat(self):1126return self.int32(5)11271128def alt(self):1129return self.int32(9)11301131def speed(self):1132return self.int16(13)11331134def temp(self):1135return self.int16(15)11361137def volt(self):1138return self.int16(17)11391140self.frame = FRAME(self.buffer[0:self.frame_length-1])1141self.buffer = self.buffer[self.frame_length:]11421143def update_read(self):1144self.buffer += self.do_read()1145while len(self.buffer):1146if len(self.buffer) == 0:1147break1148b0 = self.buffer[0]1149if sys.version_info.major < 3:1150b0 = ord(b0)1151if b0 != self.HEADER:1152self.bad_chars += 11153self.buffer = self.buffer[1:]1154continue1155if len(self.buffer) < self.frame_length:1156continue1157self.consume_frame()115811591160class FRSky(Telem):1161def __init__(self, destination_address, verbose=False):1162super(FRSky, self).__init__(destination_address, verbose=verbose)11631164self.dataid_GPS_ALT_BP = 0x011165self.dataid_TEMP1 = 0x021166self.dataid_FUEL = 0x041167self.dataid_TEMP2 = 0x051168self.dataid_GPS_ALT_AP = 0x091169self.dataid_BARO_ALT_BP = 0x101170self.dataid_GPS_SPEED_BP = 0x111171self.dataid_GPS_LONG_BP = 0x121172self.dataid_GPS_LAT_BP = 0x131173self.dataid_GPS_COURS_BP = 0x141174self.dataid_GPS_SPEED_AP = 0x191175self.dataid_GPS_LONG_AP = 0x1A1176self.dataid_GPS_LAT_AP = 0x1B1177self.dataid_BARO_ALT_AP = 0x211178self.dataid_GPS_LONG_EW = 0x221179self.dataid_GPS_LAT_NS = 0x231180self.dataid_CURRENT = 0x281181self.dataid_VFAS = 0x39118211831184class FRSkyD(FRSky):1185def __init__(self, destination_address):1186super(FRSkyD, self).__init__(destination_address)11871188self.state_WANT_START_STOP_D = 16,1189self.state_WANT_ID = 171190self.state_WANT_BYTE1 = 181191self.state_WANT_BYTE2 = 1911921193self.START_STOP_D = 0x5E1194self.BYTESTUFF_D = 0x5D11951196self.state = self.state_WANT_START_STOP_D11971198self.data_by_id = {}1199self.bad_chars = 012001201def progress_tag(self):1202return "FRSkyD"12031204def handle_data(self, dataid, value):1205self.progress("%u=%u" % (dataid, value))1206self.data_by_id[dataid] = value12071208def update_read(self):1209self.buffer += self.do_read()1210consume = None1211while len(self.buffer):1212if consume is not None:1213self.buffer = self.buffer[consume:]1214if len(self.buffer) == 0:1215break1216consume = 11217if sys.version_info.major >= 3:1218b = self.buffer[0]1219else:1220b = ord(self.buffer[0])1221if self.state == self.state_WANT_START_STOP_D:1222if b != self.START_STOP_D:1223# we may come into a stream mid-way, so we can't judge1224self.bad_chars += 11225continue1226self.state = self.state_WANT_ID1227continue1228elif self.state == self.state_WANT_ID:1229self.dataid = b1230self.state = self.state_WANT_BYTE11231continue1232elif self.state in [self.state_WANT_BYTE1, self.state_WANT_BYTE2]:1233if b == 0x5D:1234# byte-stuffed1235if len(self.buffer) < 2:1236# try again in a little while1237consume = 01238return1239if ord(self.buffer[1]) == 0x3E:1240b = self.START_STOP_D1241elif ord(self.buffer[1]) == 0x3D:1242b = self.BYTESTUFF_D1243else:1244raise ValueError("Unknown stuffed byte")1245consume = 21246if self.state == self.state_WANT_BYTE1:1247self.b1 = b1248self.state = self.state_WANT_BYTE21249continue12501251data = self.b1 | b << 81252self.handle_data(self.dataid, data)1253self.state = self.state_WANT_START_STOP_D12541255def get_data(self, dataid):1256try:1257return self.data_by_id[dataid]1258except KeyError:1259pass1260return None126112621263class SPortPacket(object):1264def __init__(self):1265self.START_STOP_SPORT = 0x7E1266self.BYTESTUFF_SPORT = 0x7D126712681269class SPortUplinkPacket(SPortPacket):1270def __init__(self, appid0, appid1, data0, data1, data2, data3):1271super(SPortUplinkPacket, self).__init__()1272self.appid0 = appid01273self.appid1 = appid11274self.data0 = data01275self.data1 = data11276self.data2 = data21277self.data3 = data31278self.SENSOR_ID_UPLINK_ID = 0x0D1279self.SPORT_UPLINK_FRAME = 0x301280self.uplink_id = self.SENSOR_ID_UPLINK_ID1281self.frame = self.SPORT_UPLINK_FRAME12821283def packed(self):1284return struct.pack(1285'<BBBBBBBB',1286self.uplink_id,1287self.frame,1288self.appid0 & 0xff,1289self.appid1 & 0xff,1290self.data0 & 0xff,1291self.data1 & 0xff,1292self.data2 & 0xff,1293self.data3 & 0xff,1294)12951296def update_checksum(self, byte):1297self.checksum += byte1298self.checksum += self.checksum >> 81299self.checksum &= 0xFF13001301def checksum(self):1302self.checksum = 01303self.update_checksum(self.frame & 0xff)1304self.update_checksum(self.appid0 & 0xff)1305self.update_checksum(self.appid1 & 0xff)1306self.update_checksum(self.data0 & 0xff)1307self.update_checksum(self.data1 & 0xff)1308self.update_checksum(self.data2 & 0xff)1309self.update_checksum(self.data3 & 0xff)1310self.checksum = 0xff - ((self.checksum & 0xff) + (self.checksum >> 8))1311return self.checksum & 0xff13121313def for_wire(self):1314out = bytearray()1315out.extend(self.packed())1316out.extend(struct.pack('<B', self.checksum()))1317stuffed = bytearray()1318stuffed.extend(struct.pack('<B', self.START_STOP_SPORT))1319for pbyte in out:1320if pbyte in [self.BYTESTUFF_SPORT,1321self.START_STOP_SPORT]:1322# bytestuff1323stuffed.append(self.BYTESTUFF_SPORT)1324stuffed.append(pbyte ^ self.SPORT_FRAME_XOR)1325else:1326stuffed.append(pbyte)1327return stuffed132813291330class SPortPollPacket(SPortPacket):1331def __init__(self, sensor):1332super(SPortPollPacket, self).__init__()1333self.sensor = sensor13341335def for_wire(self):1336return struct.pack(1337'<BB',1338self.START_STOP_SPORT,1339self.sensor & 0xff,1340)134113421343class MAVliteMessage(object):1344def __init__(self, msgid, body):1345self.msgid = msgid1346self.body = body1347self.SENSOR_ID_UPLINK_ID = 0x0D1348self.SPORT_UPLINK_FRAME = 0x3013491350def checksum_bytes(self, some_bytes):1351checksum = 01352for b in some_bytes:1353checksum += b1354checksum += checksum >> 81355checksum &= 0xFF1356return checksum13571358def to_sport_packets(self):1359ret = []1360all_bytes = bytearray([len(self.body), self.msgid])1361all_bytes.extend(self.body)13621363# insert sequence numbers:1364seq = 01365sequenced = bytearray()1366while len(all_bytes):1367chunk = all_bytes[0:5]1368all_bytes = all_bytes[5:]1369sequenced.append(seq)1370sequenced.extend(chunk)1371seq += 113721373# we may need another sport packet just for the checksum:1374if len(sequenced) % 6 == 0:1375sequenced.append(seq)1376seq += 113771378checksum = self.checksum_bytes(sequenced)1379sequenced.append(checksum)13801381while len(sequenced):1382chunk = sequenced[0:6]1383sequenced = sequenced[6:]1384chunk.extend([0] * (6-len(chunk))) # pad to 61385packet = SPortUplinkPacket(1386*chunk1387)1388ret.append(packet)1389return ret139013911392class SPortToMAVlite(object):1393def __init__(self):1394self.state_WANT_LEN = "want len"1395self.state_WANT_MSGID = "want msgid"1396self.state_WANT_PAYLOAD = "want payload"1397self.state_WANT_CHECKSUM = "want checksum"1398self.state_MESSAGE_RECEIVED = "message received"13991400self.reset()14011402def progress(self, message):1403print("SPortToMAVLite: %s" % message)14041405def reset(self):1406self.want_seq = 01407self.all_bytes = bytearray()1408self.payload = bytearray()1409self.state = self.state_WANT_LEN14101411def checksum_bytes(self, some_bytes):1412checksum = 01413for b in some_bytes:1414checksum += b1415checksum += checksum >> 81416checksum &= 0xFF1417return checksum14181419def downlink_handler(self, some_bytes):1420'''adds some_bytes into a mavlite message'''1421if some_bytes[0] == 0x00:1422self.reset()1423if some_bytes[0] != self.want_seq:1424raise NotAchievedException("Unexpected seqno; want=%u got=%u" %1425(self.want_seq, some_bytes[0]))1426self.all_bytes.append(some_bytes[0])1427self.want_seq += 11428for byte in some_bytes[1:]:1429if self.state == self.state_WANT_LEN:1430self.payload_len = byte1431self.all_bytes.append(byte)1432self.state = self.state_WANT_MSGID1433continue1434if self.state == self.state_WANT_MSGID:1435self.msgid = byte1436self.all_bytes.append(byte)1437if self.payload_len == 0:1438self.state = self.state_WANT_CHECKSUM1439else:1440self.state = self.state_WANT_PAYLOAD1441continue1442if self.state == self.state_WANT_PAYLOAD:1443self.payload.append(byte)1444self.all_bytes.append(byte)1445if len(self.payload) == self.payload_len:1446self.state = self.state_WANT_CHECKSUM1447continue1448if self.state == self.state_WANT_CHECKSUM:1449calculated_checksum = self.checksum_bytes(self.all_bytes)1450if calculated_checksum != byte:1451raise Exception("Checksum failure (calc=%u) (recv=%u)" % (calculated_checksum, byte))1452self.state = self.state_MESSAGE_RECEIVED1453break14541455def get_message(self):1456if self.state != self.state_MESSAGE_RECEIVED:1457raise Exception("Wrong state")1458return MAVliteMessage(self.msgid, self.payload)145914601461class FRSkySPort(FRSky):1462def __init__(self, destination_address, verbose=True, get_time=time.time):1463super(FRSkySPort, self).__init__(1464destination_address,1465verbose=verbose1466)14671468self.get_time = get_time14691470self.state_SEND_POLL = "sendpoll"1471self.state_WANT_FRAME_TYPE = "want_frame_type"1472self.state_WANT_ID1 = "want_id1"1473self.state_WANT_ID2 = "want id2"1474self.state_WANT_DATA = "want data"1475self.state_WANT_CRC = "want crc"14761477self.START_STOP_SPORT = 0x7E1478self.BYTESTUFF_SPORT = 0x7D1479self.SPORT_DATA_FRAME = 0x101480self.SPORT_DOWNLINK_FRAME = 0x321481self.SPORT_FRAME_XOR = 0x2014821483self.SENSOR_ID_VARIO = 0x00 # Sensor ID 01484self.SENSOR_ID_FAS = 0x22 # Sensor ID 21485self.SENSOR_ID_GPS = 0x83 # Sensor ID 31486self.SENSOR_ID_RPM = 0xE4 # Sensor ID 41487self.SENSOR_ID_SP2UR = 0xC6 # Sensor ID 61488self.SENSOR_ID_27 = 0x1B # Sensor ID 2714891490# MAVlite support:1491self.SENSOR_ID_DOWNLINK1_ID = 0x341492self.SENSOR_ID_DOWNLINK2_ID = 0x671493self.SENSOR_ID_UPLINK_ID = 0x0D14941495self.state = self.state_WANT_FRAME_TYPE14961497self.data_by_id = {}1498self.dataid_counts = {}1499self.bad_chars = 015001501self.poll_sent = 01502self.sensor_id_poll_counts = {}15031504self.id_descriptions = {15050x5000: "status text (dynamic)",15060x5006: "Attitude and range (dynamic)",15070x800: "GPS lat or lon (600 with 1 sensor)",15080x5005: "Vel and Yaw",15090x5001: "AP status",15100x5002: "GPS Status",15110x5004: "Home",15120x5008: "Battery 2 status",15130x5003: "Battery 1 status",15140x5007: "parameters",15150x500A: "rpm",15160x500B: "terrain",15170x500C: "wind",15181519# SPort non-passthrough:15200x082F: "GALT", # gps altitude integer cm15210x040F: "TMP1", # Tmp115220x060F: "Fuel", # fuel % 0-10015230x041F: "TMP2", # Tmp215240x010F: "ALT", # baro alt cm15250x083F: "GSPD", # gps speed integer mm/s15260x084F: "HDG", # yaw in cd15270x020F: "CURR", # current dA15280x011F: "VSPD", # vertical speed cm/s15290x021F: "VFAS", # battery 1 voltage cV1530# 0x800: "GPS", ## comments as duplicated dictrionary key15310x050E: "RPM1",153215330x34: "DOWNLINK1_ID",15340x67: "DOWNLINK2_ID",15350x0D: "UPLINK_ID",1536}15371538self.sensors_to_poll = [1539self.SENSOR_ID_VARIO,1540self.SENSOR_ID_FAS,1541self.SENSOR_ID_GPS,1542self.SENSOR_ID_RPM,1543self.SENSOR_ID_SP2UR,1544]1545self.next_sensor_id_to_poll = 0 # offset into sensors_to_poll15461547self.data_downlink_handler = None15481549self.last_poll_sensor = None1550self.last_data_time = None15511552def progress_tag(self):1553return "FRSkySPort"15541555def handle_data_downlink(self, some_bytes):1556self.progress("DOWNLINK %s" % (str(some_bytes),))1557if self.data_downlink_handler is not None:1558self.data_downlink_handler(some_bytes)1559self.last_data_time = self.get_time()15601561def handle_data(self, dataid, value):1562if dataid not in self.id_descriptions:1563raise KeyError("dataid 0x%02x" % dataid)1564self.progress("%s (0x%x)=%u" % (self.id_descriptions[dataid], dataid, value))1565self.data_by_id[dataid] = value1566if dataid not in self.dataid_counts:1567self.dataid_counts[dataid] = 01568self.dataid_counts[dataid] += 11569self.last_data_time = self.get_time()15701571def dump_dataid_counts_as_progress_messages(self):1572for dataid in self.dataid_counts:1573self.progress("0x%x: %u (%s)" % (dataid, self.dataid_counts[dataid], self.id_descriptions[dataid]))15741575def dump_sensor_id_poll_counts_as_progress_messages(self):1576for sensor_id in self.sensor_id_poll_counts:1577self.progress("(0x%x): %u" % (sensor_id, self.sensor_id_poll_counts[sensor_id]))15781579def read_bytestuffed_byte(self):1580if sys.version_info.major >= 3:1581b = self.buffer[0]1582else:1583b = ord(self.buffer[0])1584if b == 0x7D:1585# byte-stuffed1586if len(self.buffer) < 2:1587self.consume = 01588return None1589self.consume = 21590if sys.version_info.major >= 3:1591b2 = self.buffer[1]1592else:1593b2 = ord(self.buffer[1])1594if b2 == 0x5E:1595return self.START_STOP_SPORT1596if b2 == 0x5D:1597return self.BYTESTUFF_SPORT1598raise ValueError("Unknown stuffed byte (0x%02x)" % b2)1599return b16001601def calc_crc(self, byte):1602self.crc += byte1603self.crc += self.crc >> 81604self.crc &= 0xFF16051606def next_sensor(self):1607ret = self.sensors_to_poll[self.next_sensor_id_to_poll]1608self.next_sensor_id_to_poll += 11609if self.next_sensor_id_to_poll >= len(self.sensors_to_poll):1610self.next_sensor_id_to_poll = 01611return ret16121613def check_poll(self):1614now = self.get_time()1615# self.progress("check poll (%u)" % now)16161617# sometimes ArduPilot will not respond to a poll - for1618# example, if you poll an unhealthy RPM sensor then we will1619# *never* get a response back. So we must re-poll (which1620# moves onto the next sensor):1621if now - self.poll_sent > 5:1622if self.last_poll_sensor is None:1623self.progress("Re-polling (last poll sensor was None)")1624else:1625msg = ("Re-polling (last_poll_sensor=0x%02x state=%s)" %1626(self.last_poll_sensor, self.state))1627self.progress(msg)1628if self.state != self.state_WANT_FRAME_TYPE:1629raise ValueError("Expected to be wanting a frame type when repolling (state=%s)" % str(self.state))1630self.state = self.state_SEND_POLL16311632if self.state == self.state_SEND_POLL:1633sensor_id = self.next_sensor()1634self.progress("Sending poll for 0x%02x" % sensor_id)1635self.last_poll_sensor = sensor_id1636if sensor_id not in self.sensor_id_poll_counts:1637self.sensor_id_poll_counts[sensor_id] = 01638self.sensor_id_poll_counts[sensor_id] += 11639packet = SPortPollPacket(sensor_id)1640self.send_sport_packet(packet)1641self.state = self.state_WANT_FRAME_TYPE1642self.poll_sent = now16431644def send_sport_packets(self, packets):1645for packet in packets:1646self.send_sport_packet(packet)16471648def send_sport_packet(self, packet):1649stuffed = packet.for_wire()1650self.progress("Sending (%s) (%u)" %1651(["0x%02x" % x for x in bytearray(stuffed)], len(stuffed)))1652self.port.sendall(stuffed)16531654def send_mavlite_param_request_read(self, parameter_name):1655mavlite_msg = MAVliteMessage(1656mavutil.mavlink.MAVLINK_MSG_ID_PARAM_REQUEST_READ,1657bytearray(parameter_name.encode())1658)16591660packets = mavlite_msg.to_sport_packets()16611662self.send_sport_packets(packets)16631664def send_mavlite_param_set(self, parameter_name, value):1665out = bytearray(struct.pack("<f", value))1666out.extend(parameter_name.encode())16671668mavlite_msg = MAVliteMessage(1669mavutil.mavlink.MAVLINK_MSG_ID_PARAM_SET,1670out1671)16721673packets = mavlite_msg.to_sport_packets()16741675self.send_sport_packets(packets)16761677def send_mavlite_command_long(1678self,1679command,1680p1=None,1681p2=None,1682p3=None,1683p4=None,1684p5=None,1685p6=None,1686p7=None,1687):1688params = bytearray()1689seen_none = False1690for p in p1, p2, p3, p4, p5, p6, p7:1691if p is None:1692seen_none = True1693continue1694if seen_none:1695raise ValueError("Can't have values after Nones!")1696params.extend(bytearray(struct.pack("<f", p)))16971698out = bytearray(struct.pack("<H", command)) # first two bytes are command-id1699options = len(params) // 4 # low-three-bits is parameter count1700out.extend(bytearray(struct.pack("<B", options))) # second byte is options1701out.extend(params) # then the float values17021703mavlite_msg = MAVliteMessage(1704mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_LONG,1705out1706)17071708packets = mavlite_msg.to_sport_packets()17091710self.send_sport_packets(packets)17111712def update(self):1713if not self.connected:1714if not self.connect():1715self.progress("Failed to connect")1716return1717self.do_sport_read()1718self.check_poll()17191720def do_sport_read(self):1721self.buffer += self.do_read()1722self.consume = None1723while len(self.buffer):1724if self.consume is not None:1725self.buffer = self.buffer[self.consume:]1726if len(self.buffer) == 0:1727break1728self.consume = 11729if sys.version_info.major >= 3:1730b = self.buffer[0]1731else:1732b = ord(self.buffer[0])1733# self.progress("Have (%s) bytes state=%s b=0x%02x" % (str(len(self.buffer)), str(self.state), b));1734if self.state == self.state_WANT_FRAME_TYPE:1735if b in [self.SPORT_DATA_FRAME, self.SPORT_DOWNLINK_FRAME]:1736self.frame = b1737self.crc = 01738self.calc_crc(b)1739self.state = self.state_WANT_ID11740continue1741# we may come into a stream mid-way, so we can't judge1742self.progress("############# Bad char %x" % b)1743raise ValueError("Bad char (0x%02x)" % b)1744self.bad_chars += 11745continue1746elif self.state == self.state_WANT_ID1:1747self.id1 = self.read_bytestuffed_byte()1748if self.id1 is None:1749break1750self.calc_crc(self.id1)1751self.state = self.state_WANT_ID21752continue1753elif self.state == self.state_WANT_ID2:1754self.id2 = self.read_bytestuffed_byte()1755if self.id2 is None:1756break1757self.calc_crc(self.id2)1758self.state = self.state_WANT_DATA1759self.data_bytes = []1760self.data = 01761continue1762elif self.state == self.state_WANT_DATA:1763data_byte = self.read_bytestuffed_byte()1764if data_byte is None:1765break1766self.calc_crc(data_byte)1767self.data = self.data | (data_byte << (8*(len(self.data_bytes))))1768self.data_bytes.append(data_byte)1769if len(self.data_bytes) == 4:1770self.state = self.state_WANT_CRC1771continue1772elif self.state == self.state_WANT_CRC:1773crc = self.read_bytestuffed_byte()1774if crc is None:1775break1776self.crc = 0xFF - self.crc1777dataid = (self.id2 << 8) | self.id11778if self.crc != crc:1779self.progress("Incorrect frsky checksum (received=%02x calculated=%02x id=0x%x)" % (crc, self.crc, dataid))1780# raise ValueError("Incorrect frsky checksum (want=%02x got=%02x id=0x%x)" % (crc, self.crc, dataid))1781else:1782if self.frame == self.SPORT_DOWNLINK_FRAME:1783self.handle_data_downlink([1784self.id1,1785self.id2,1786self.data_bytes[0],1787self.data_bytes[1],1788self.data_bytes[2],1789self.data_bytes[3]]1790)1791else:1792self.handle_data(dataid, self.data)1793self.state = self.state_SEND_POLL1794elif self.state == self.state_SEND_POLL:1795# this is done in check_poll1796self.progress("in send_poll state")1797pass1798else:1799raise ValueError("Unknown state (%s)" % self.state)18001801def get_data(self, dataid):1802try:1803return self.data_by_id[dataid]1804except KeyError:1805pass1806return None180718081809class FRSkyPassThrough(FRSkySPort):1810def __init__(self, destination_address, get_time=time.time):1811super(FRSkyPassThrough, self).__init__(destination_address,1812get_time=get_time)18131814self.sensors_to_poll = [self.SENSOR_ID_27]18151816def progress_tag(self):1817return "FRSkyPassthrough"181818191820class LocationInt(object):1821def __init__(self, lat, lon, alt, yaw):1822self.lat = lat1823self.lon = lon1824self.alt = alt1825self.yaw = yaw182618271828class Test(object):1829'''a test definition - information about a test'''1830def __init__(self, function, kwargs={}, attempts=1, speedup=None):1831self.name = function.__name__1832self.description = function.__doc__1833if self.description is None:1834raise ValueError("%s is missing a docstring" % self.name)1835self.function = function1836self.kwargs = kwargs1837self.attempts = attempts1838self.speedup = speedup183918401841class Result(object):1842'''a test result - pass, fail, exception, runtime, ....'''1843def __init__(self, test):1844self.test = test1845self.reason = None1846self.exception = None1847self.debug_filename = None1848self.time_elapsed = 0.01849# self.passed = False18501851def __str__(self):1852ret = " %s (%s)" % (self.test.name, self.test.description)1853if self.passed:1854return f"{ret} OK"1855if self.reason is not None:1856ret += f" ({self.reason} )"1857if self.exception is not None:1858ret += f" ({str(self.exception)})"1859if self.debug_filename is not None:1860ret += f" (see {self.debug_filename})"1861if self.time_elapsed is not None:1862ret += f" (duration {self.time_elapsed} s)"1863return ret186418651866class ValgrindFailedResult(Result):1867'''a custom Result to allow passing of Vaglrind failures around'''1868def __init__(self):1869super(ValgrindFailedResult, self).__init__(None)1870self.passed = False18711872def __str__(self):1873return "Valgrind error detected"187418751876class TestSuite(ABC):1877"""Base abstract class.1878It implements the common function for all vehicle types.1879"""1880def __init__(self,1881binary,1882valgrind=False,1883callgrind=False,1884gdb=False,1885gdb_no_tui=False,1886speedup=None,1887frame=None,1888params=None,1889gdbserver=False,1890lldb=False,1891breakpoints=[],1892disable_breakpoints=False,1893viewerip=None,1894use_map=False,1895_show_test_timings=False,1896logs_dir=None,1897force_ahrs_type=None,1898replay=False,1899sup_binaries=[],1900reset_after_every_test=False,1901force_32bit=False,1902ubsan=False,1903ubsan_abort=False,1904num_aux_imus=0,1905dronecan_tests=False,1906generate_junit=False,1907enable_fgview=False,1908build_opts={}):19091910self.start_time = time.time()19111912if binary is None:1913raise ValueError("Should always have a binary")19141915self.binary = binary1916self.valgrind = valgrind1917self.callgrind = callgrind1918self.gdb = gdb1919self.gdb_no_tui = gdb_no_tui1920self.lldb = lldb1921self.frame = frame1922self.params = params1923self.gdbserver = gdbserver1924self.breakpoints = breakpoints1925self.disable_breakpoints = disable_breakpoints1926self.speedup = speedup1927if self.speedup is None:1928self.speedup = self.default_speedup()1929self.sup_binaries = sup_binaries1930self.reset_after_every_test = reset_after_every_test1931self.force_32bit = force_32bit1932self.ubsan = ubsan1933self.ubsan_abort = ubsan_abort1934self.build_opts = build_opts1935self.num_aux_imus = num_aux_imus1936self.generate_junit = generate_junit1937if generate_junit:1938try:1939spec = importlib.util.find_spec("junitparser")1940if spec is None:1941raise ImportError1942except ImportError as e:1943raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python3 -m pip install junitparser")19441945self.mavproxy = None1946self._mavproxy = None # for auto-cleanup on failed tests1947self.mav = None1948self.viewerip = viewerip1949self.use_map = use_map1950self.contexts = []1951self.context_push()1952self.buildlog = None1953self.copy_tlog = False1954self.logfile = None1955self.max_set_rc_timeout = 01956self.last_wp_load = 01957self.forced_post_test_sitl_reboots = 01958self.run_tests_called = False1959self._show_test_timings = _show_test_timings1960self.test_timings = dict()1961self.total_waiting_to_arm_time = 01962self.waiting_to_arm_count = 01963self.force_ahrs_type = force_ahrs_type1964self.replay = replay1965if self.force_ahrs_type is not None:1966self.force_ahrs_type = int(self.force_ahrs_type)1967self.logs_dir = logs_dir1968self.timesync_number = 1371969self.last_progress_sent_as_statustext = None1970self.last_heartbeat_time_ms = None1971self.last_heartbeat_time_wc_s = 01972self.in_drain_mav = False1973self.tlog = None1974self.enable_fgview = enable_fgview19751976self.rc_thread = None1977self.rc_thread_should_quit = False1978self.rc_queue = Queue.Queue()19791980self.expect_list = []19811982self.start_mavproxy_count = 019831984self.last_sim_time_cached = 01985self.last_sim_time_cached_wallclock = 019861987# to autopilot we do not want to go to the internet for tiles,1988# usually. Set this to False to gather tiles from internet in1989# the cae there are new tiles required, then add them to the1990# repo and set this back to false:1991self.terrain_in_offline_mode = True1992self.elevationmodel = mp_elevation.ElevationModel(1993cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"),1994offline=self.terrain_in_offline_mode1995)1996self.terrain_data_messages_sent = 0 # count of messages back1997self.dronecan_tests = dronecan_tests1998self.statustext_id = 11999self.message_hooks = [] # functions or MessageHook instances20002001def __del__(self):2002if self.rc_thread is not None:2003self.progress("Joining RC thread in __del__")2004self.rc_thread_should_quit = True2005self.rc_thread.join()2006self.rc_thread = None20072008def default_speedup(self):2009return 820102011def progress(self, text, send_statustext=True):2012"""Display autotest progress text."""2013delta_time = time.time() - self.start_time2014formatted_text = "AT-%06.1f: %s" % (delta_time, text)2015print(formatted_text)2016if (send_statustext and2017self.mav is not None and2018self.mav.port is not None and2019self.last_progress_sent_as_statustext != text):2020self.send_statustext(formatted_text)2021self.last_progress_sent_as_statustext = text20222023# following two functions swiped from autotest.py:2024@staticmethod2025def buildlogs_dirpath():2026return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))20272028def sitl_home(self):2029HOME = self.sitl_start_location()2030return "%f,%f,%u,%u" % (HOME.lat,2031HOME.lng,2032HOME.alt,2033HOME.heading)20342035def mavproxy_version(self):2036'''return the current version of mavproxy as a tuple e.g. (1,8,8)'''2037return util.MAVProxy_version()20382039def mavproxy_version_gt(self, major, minor, point):2040if os.getenv("AUTOTEST_FORCE_MAVPROXY_VERSION", None) is not None:2041return True2042(got_major, got_minor, got_point) = self.mavproxy_version()2043self.progress("Got: %s.%s.%s" % (got_major, got_minor, got_point))2044if got_major > major:2045return True2046elif got_major < major:2047return False2048if got_minor > minor:2049return True2050elif got_minor < minor:2051return False2052return got_point > point20532054def open_mavproxy_logfile(self):2055return MAVProxyLogFile()20562057def buildlogs_path(self, path):2058"""Return a string representing path in the buildlogs directory."""2059bits = [self.buildlogs_dirpath()]2060if isinstance(path, list):2061bits.extend(path)2062else:2063bits.append(path)2064return os.path.join(*bits)20652066def sitl_streamrate(self):2067"""Allow subclasses to override SITL streamrate."""2068return 1020692070def adjust_ardupilot_port(self, port):2071'''adjust port in case we do not wish to use the default range (5760 and 5501 etc)'''2072return port20732074def spare_network_port(self, offset=0):2075'''returns a network port which should be able to be bound'''2076if offset > 2:2077raise ValueError("offset too large")2078return 8000 + offset20792080def autotest_connection_string_to_ardupilot(self):2081return "tcp:127.0.0.1:%u" % self.adjust_ardupilot_port(5760)20822083def sitl_rcin_port(self, offset=0):2084if offset > 2:2085raise ValueError("offset too large")2086return 5501 + offset20872088def mavproxy_options(self):2089"""Returns options to be passed to MAVProxy."""2090ret = [2091'--streamrate=%u' % self.sitl_streamrate(),2092'--target-system=%u' % self.sysid_thismav(),2093'--target-component=1',2094]2095if self.viewerip:2096ret.append("--out=%s:14550" % self.viewerip)2097if self.use_map:2098ret.append('--map')20992100return ret21012102def vehicleinfo_key(self):2103return self.log_name()21042105def repeatedly_apply_parameter_filepath(self, filepath):2106if False:2107return self.repeatedly_apply_parameter_filepath_mavproxy(filepath)2108parameters = mavparm.MAVParmDict()2109# correct_parameters = set()2110if not parameters.load(filepath):2111raise ValueError("Param load failed")2112param_dict = {}2113for p in parameters.keys():2114param_dict[p] = parameters[p]2115self.set_parameters(param_dict)21162117def repeatedly_apply_parameter_filepath_mavproxy(self, filepath):2118'''keep applying a parameter file until no parameters changed'''2119for i in range(0, 3):2120self.mavproxy.send("param load %s\n" % filepath)2121while True:2122line = self.mavproxy.readline()2123match = re.match(".*Loaded [0-9]+ parameters.*changed ([0-9]+)",2124line)2125if match is not None:2126if int(match.group(1)) == 0:2127return2128break2129raise NotAchievedException()21302131def apply_defaultfile_parameters(self):2132"""Apply parameter file."""2133self.progress("Applying default parameters file")2134# setup test parameters2135if self.params is None:2136self.params = self.model_defaults_filepath(self.frame)2137for x in self.params:2138self.repeatedly_apply_parameter_filepath(x)21392140def count_lines_in_filepath(self, filepath):2141return len([i for i in open(filepath)])21422143def count_expected_fence_lines_in_filepath(self, filepath):2144count = 02145is_qgc = False2146for i in open(filepath):2147i = re.sub("#.*", "", i) # trim comments2148if i.isspace():2149# skip empty lines2150continue2151if re.match("QGC", i):2152# skip QGC header line2153is_qgc = True2154continue2155count += 12156if is_qgc:2157count += 2 # file doesn't include return point + closing point2158return count21592160def load_fence_using_mavproxy(self, mavproxy, filename):2161self.set_parameter("FENCE_TOTAL", 0)2162filepath = os.path.join(testdir, self.current_test_name_directory, filename)2163count = self.count_expected_fence_lines_in_filepath(filepath)2164mavproxy.send('fence load %s\n' % filepath)2165# self.mavproxy.expect("Loaded %u (geo-)?fence" % count)2166tstart = self.get_sim_time_cached()2167while True:2168t2 = self.get_sim_time_cached()2169if t2 - tstart > 10:2170raise AutoTestTimeoutException("Failed to do load")2171newcount = self.get_parameter("FENCE_TOTAL")2172self.progress("fence total: %u want=%u" % (newcount, count))2173if count == newcount:2174break2175self.delay_sim_time(1)21762177def get_fence_point(self, idx, target_system=1, target_component=1):2178self.mav.mav.fence_fetch_point_send(target_system,2179target_component,2180idx)2181m = self.assert_receive_message("FENCE_POINT", timeout=2)2182self.progress("m: %s" % str(m))2183if m.idx != idx:2184raise NotAchievedException("Invalid idx returned (want=%u got=%u)" %2185(idx, m.seq))2186return m21872188def fencepoint_protocol_epsilon(self):2189return 0.0000221902191def roundtrip_fencepoint_protocol(self, offset, count, lat, lng, target_system=1, target_component=1):2192self.progress("Sending FENCE_POINT offs=%u count=%u" % (offset, count))2193self.mav.mav.fence_point_send(target_system,2194target_component,2195offset,2196count,2197lat,2198lng)21992200self.progress("Requesting fence point")2201m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)2202if abs(m.lat - lat) > self.fencepoint_protocol_epsilon():2203raise NotAchievedException("Did not get correct lat in fencepoint: got=%f want=%f" % (m.lat, lat))2204if abs(m.lng - lng) > self.fencepoint_protocol_epsilon():2205raise NotAchievedException("Did not get correct lng in fencepoint: got=%f want=%f" % (m.lng, lng))2206self.progress("Roundtrip OK")22072208def roundtrip_fence_using_fencepoint_protocol(self, loc_list, target_system=1, target_component=1, ordering=None):2209count = len(loc_list)2210offset = 02211self.set_parameter("FENCE_TOTAL", count)2212if ordering is None:2213ordering = range(count)2214elif len(ordering) != len(loc_list):2215raise ValueError("ordering list length mismatch")22162217for offset in ordering:2218loc = loc_list[offset]2219self.roundtrip_fencepoint_protocol(offset,2220count,2221loc.lat,2222loc.lng,2223target_system,2224target_component)22252226self.progress("Validating uploaded fence")2227returned_count = self.get_parameter("FENCE_TOTAL")2228if returned_count != count:2229raise NotAchievedException("Returned count mismatch (want=%u got=%u)" %2230(count, returned_count))2231for i in range(count):2232self.progress("Requesting fence point")2233m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)2234if abs(m.lat-loc.lat) > self.fencepoint_protocol_epsilon():2235raise NotAchievedException("Returned lat mismatch (want=%f got=%f" %2236(loc.lat, m.lat))2237if abs(m.lng-loc.lng) > self.fencepoint_protocol_epsilon():2238raise NotAchievedException("Returned lng mismatch (want=%f got=%f" %2239(loc.lng, m.lng))2240if m.count != count:2241raise NotAchievedException("Count mismatch (want=%u got=%u)" %2242(count, m.count))22432244def load_fence(self, filename):2245filepath = os.path.join(testdir, self.current_test_name_directory, filename)2246if not os.path.exists(filepath):2247filepath = self.generic_mission_filepath_for_filename(filename)2248self.progress("Loading fence from (%s)" % str(filepath))2249locs = []2250for line in open(filepath, 'rb'):2251if len(line) == 0:2252continue2253m = re.match(r"([-\d.]+)\s+([-\d.]+)\s*", line.decode('ascii'))2254if m is None:2255raise ValueError("Did not match (%s)" % line)2256locs.append(mavutil.location(float(m.group(1)), float(m.group(2)), 0, 0))2257if self.is_plane():2258# create return point as the centroid:2259total_lat = 02260total_lng = 02261total_cnt = 02262for loc in locs:2263total_lat += loc.lat2264total_lng += loc.lng2265total_cnt += 12266locs2 = [mavutil.location(total_lat/total_cnt,2267total_lng/total_cnt,22680,22690)] # return point2270locs2.extend(locs)2271locs2.append(copy.copy(locs2[1]))2272return self.roundtrip_fence_using_fencepoint_protocol(locs2)22732274self.upload_fences_from_locations([2275(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),2276])22772278def load_fence_using_mavwp(self, filename):2279filepath = os.path.join(testdir, self.current_test_name_directory, filename)2280if not os.path.exists(filepath):2281filepath = self.generic_mission_filepath_for_filename(filename)2282self.progress("Loading fence from (%s)" % str(filepath))2283items = self.mission_item_protocol_items_from_filepath(mavwp.MissionItemProtocol_Fence, filepath)2284self.check_fence_upload_download(items)22852286def send_reboot_command(self):2287self.mav.mav.command_long_send(self.sysid_thismav(),22881,2289mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,22901, # confirmation22911, # reboot autopilot22920,22930,22940,22950,22960,22970)22982299def reboot_check_valgrind_log(self):2300valgrind_log = util.valgrind_log_filepath(binary=self.binary,2301model=self.frame)2302if os.path.isfile(valgrind_log) and (os.path.getsize(valgrind_log) > 0):2303backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))2304shutil.move(valgrind_log, backup_valgrind_log)23052306def run_cmd_reboot(self):2307self.run_cmd_int(2308mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,2309p1=1, # reboot autopilot2310)23112312def run_cmd_enable_high_latency(self, new_state, run_cmd=None):2313if run_cmd is None:2314run_cmd = self.run_cmd2315p1 = 02316if new_state:2317p1 = 123182319run_cmd(2320mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY,2321p1=p1, # enable/disable2322)23232324def reboot_sitl_mav(self, required_bootcount=None, force=False):2325"""Reboot SITL instance using mavlink and wait for it to reconnect."""2326# we must make sure that stats have been reset - otherwise2327# when we reboot we'll reset statistics again and lose our2328# STAT_BOOTCNT increment:2329tstart = time.time()2330while True:2331if time.time() - tstart > 30:2332raise NotAchievedException("STAT_RESET did not go non-zero")2333if self.get_parameter('STAT_RESET', timeout_in_wallclock=True) != 0:2334break23352336old_bootcount = self.get_parameter('STAT_BOOTCNT')2337# ardupilot SITL may actually NAK the reboot; replace with2338# run_cmd when we don't do that.2339do_context = False2340if self.valgrind or self.callgrind:2341self.reboot_check_valgrind_log()2342self.progress("Stopping and restarting SITL")2343if getattr(self, 'valgrind_restart_customisations', None) is not None:2344self.customise_SITL_commandline(2345self.valgrind_restart_customisations,2346model=self.valgrind_restart_model,2347defaults_filepath=self.valgrind_restart_defaults_filepath,2348)2349else:2350self.stop_SITL()2351self.start_SITL(wipe=False)2352else:2353# receiving an ACK from the process turns out to be really2354# quite difficult. So just send it and hope for the best.2355self.progress("Sending reboot command")2356p6 = 02357if force:2358p6 = 20190226 # magic force-reboot value2359self.send_cmd(2360mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,2361p1=1,2362p2=1,2363p6=p6,2364)2365do_context = True2366if do_context:2367self.context_push()23682369def hook(mav, m):2370if m.get_type() != 'COMMAND_ACK':2371return2372if m.command != mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:2373return2374self.progress("While awaiting reboot received (%s)" % str(m))2375if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:2376raise NotAchievedException("Bad reboot ACK detected")2377self.install_message_hook_context(hook)23782379self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)23802381if do_context:2382self.context_pop()23832384def send_cmd_enter_cpu_lockup(self):2385"""Poke ArduPilot to stop the main loop from running"""2386self.mav.mav.command_long_send(self.sysid_thismav(),23871,2388mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,23891, # confirmation239042, # lockup autopilot239124, # no, really, we mean it239271, # seriously, we're not kidding239393, # we know exactly what we're23940,23950,23960)23972398def reboot_sitl(self,2399required_bootcount=None,2400force=False,2401check_position=True,2402mark_context=True,2403startup_location_dist_max=1,2404):2405"""Reboot SITL instance and wait for it to reconnect."""2406if self.armed() and not force:2407raise NotAchievedException("Reboot attempted while armed")2408self.progress("Rebooting SITL")2409self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force)2410self.do_heartbeats(force=True)2411if check_position and self.frame != 'sailboat': # sailboats drift with wind!2412self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max)2413if mark_context:2414self.context_get().reboot_sitl_was_done = True24152416def reboot_sitl_mavproxy(self, required_bootcount=None):2417"""Reboot SITL instance using MAVProxy and wait for it to reconnect."""2418old_bootcount = self.get_parameter('STAT_BOOTCNT')2419self.mavproxy.send("reboot\n")2420self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)24212422def detect_and_handle_reboot(self, old_bootcount, required_bootcount=None, timeout=10):2423tstart = time.time()2424if required_bootcount is None:2425required_bootcount = old_bootcount + 12426while True:2427if time.time() - tstart > timeout:2428raise AutoTestTimeoutException("Did not detect reboot")2429try:2430current_bootcount = self.get_parameter('STAT_BOOTCNT',2431timeout=1,2432attempts=1,2433verbose=True,2434timeout_in_wallclock=True)2435self.progress("current=%s required=%u" %2436(str(current_bootcount), required_bootcount))2437if current_bootcount == required_bootcount:2438break2439except NotAchievedException:2440pass2441except AutoTestTimeoutException:2442pass2443except ConnectionResetError:2444pass2445except socket.error:2446pass2447except Exception as e:2448self.progress("Got unexpected exception (%s)" % str(type(e)))2449pass24502451# empty mav to avoid getting old timestamps:2452self.do_timesync_roundtrip(timeout_in_wallclock=True)24532454self.progress("Calling initialise-after-reboot")2455self.initialise_after_reboot_sitl()24562457def scripting_restart(self):2458'''restart scripting subsystem'''2459self.progress("Restarting Scripting")2460self.run_cmd_int(2461mavutil.mavlink.MAV_CMD_SCRIPTING,2462p1=mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,2463timeout=5,2464)24652466def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):2467'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''2468self.do_timesync_roundtrip(timeout_in_wallclock=True)2469tstart = time.time()2470while True:2471if time.time() - tstart > timeout:2472raise NotAchievedException("Failed to set streamrate")2473self.mav.mav.request_data_stream_send(24741,24751,2476stream,2477streamrate,24781)2479m = self.mav.recv_match(type='SYSTEM_TIME',2480blocking=True,2481timeout=1)2482if m is not None:2483break24842485def set_streamrate_mavproxy(self, streamrate, timeout=10):2486tstart = time.time()2487while True:2488if time.time() - tstart > timeout:2489raise AutoTestTimeoutException("stream rate change failed")24902491self.mavproxy.send("set streamrate %u\n" % (streamrate))2492self.mavproxy.send("set streamrate\n")2493try:2494self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1)2495except pexpect.TIMEOUT:2496continue2497rate = self.mavproxy.match.group(1)2498# self.progress("rate: %s" % str(rate))2499if int(rate) == int(streamrate):2500break25012502if streamrate <= 0:2503return25042505self.progress("Waiting for SYSTEM_TIME for confirmation streams are working")2506self.drain_mav_unparsed()2507timeout = 602508tstart = time.time()2509while True:2510self.drain_all_pexpects()2511if time.time() - tstart > timeout:2512raise NotAchievedException("Did not get SYSTEM_TIME within %f seconds" % timeout)2513m = self.mav.recv_match(timeout=0.1)2514if m is None:2515continue2516# self.progress("Received (%s)" % str(m))2517if m.get_type() == 'SYSTEM_TIME':2518break2519self.drain_mav()25202521def htree_from_xml(self, xml_filepath):2522'''swiped from mavproxy_param.py'''2523xml = open(xml_filepath, 'rb').read()2524from lxml import objectify2525objectify.enable_recursive_str()2526tree = objectify.fromstring(xml)2527htree = {}2528for p in tree.vehicles.parameters.param:2529n = p.get('name').split(':')[1]2530htree[n] = p2531for lib in tree.libraries.parameters:2532for p in lib.param:2533n = p.get('name')2534htree[n] = p2535return htree25362537def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None):2538self.progress("Sending ABSD_VEHICLE message")2539new = here2540if offset_ne is not None:2541new = self.offset_location_ne(new, offset_ne[0], offset_ne[1])2542self.mav.mav.adsb_vehicle_send(254337, # ICAO address2544int(new.lat * 1e7),2545int(new.lng * 1e7),2546mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,2547int(here.alt*1000 + 10000), # 10m up25480, # heading in cdeg25490, # horizontal velocity cm/s25500, # vertical velocity cm/s2551"bob".encode("ascii"), # callsign2552mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,25531, # time since last communication255465535, # flags255517 # squawk2556)25572558def get_sim_parameter_documentation_get_whitelist(self):2559# common parameters2560ret = set([2561"SIM_ACC_TRIM_X",2562"SIM_ACC_TRIM_Y",2563"SIM_ACC_TRIM_Z",2564"SIM_ARSPD2_OFS",2565"SIM_ARSPD2_RND",2566"SIM_ARSPD_OFS",2567"SIM_ARSPD_RND",2568"SIM_FTOWESC_ENA",2569"SIM_FTOWESC_POW",2570"SIM_IE24_ENABLE",2571"SIM_IE24_ERROR",2572"SIM_IE24_STATE",2573"SIM_IMUT1_ACC1_X",2574"SIM_IMUT1_ACC1_Y",2575"SIM_IMUT1_ACC1_Z",2576"SIM_IMUT1_ACC2_X",2577"SIM_IMUT1_ACC2_Y",2578"SIM_IMUT1_ACC2_Z",2579"SIM_IMUT1_ACC3_X",2580"SIM_IMUT1_ACC3_Y",2581"SIM_IMUT1_ACC3_Z",2582"SIM_IMUT1_ENABLE",2583"SIM_IMUT1_GYR1_X",2584"SIM_IMUT1_GYR1_Y",2585"SIM_IMUT1_GYR1_Z",2586"SIM_IMUT1_GYR2_X",2587"SIM_IMUT1_GYR2_Y",2588"SIM_IMUT1_GYR2_Z",2589"SIM_IMUT1_GYR3_X",2590"SIM_IMUT1_GYR3_Y",2591"SIM_IMUT1_GYR3_Z",2592"SIM_IMUT1_TMAX",2593"SIM_IMUT1_TMIN",2594"SIM_IMUT2_ACC1_X",2595"SIM_IMUT2_ACC1_Y",2596"SIM_IMUT2_ACC1_Z",2597"SIM_IMUT2_ACC2_X",2598"SIM_IMUT2_ACC2_Y",2599"SIM_IMUT2_ACC2_Z",2600"SIM_IMUT2_ACC3_X",2601"SIM_IMUT2_ACC3_Y",2602"SIM_IMUT2_ACC3_Z",2603"SIM_IMUT2_ENABLE",2604"SIM_IMUT2_GYR1_X",2605"SIM_IMUT2_GYR1_Y",2606"SIM_IMUT2_GYR1_Z",2607"SIM_IMUT2_GYR2_X",2608"SIM_IMUT2_GYR2_Y",2609"SIM_IMUT2_GYR2_Z",2610"SIM_IMUT2_GYR3_X",2611"SIM_IMUT2_GYR3_Y",2612"SIM_IMUT2_GYR3_Z",2613"SIM_IMUT2_TMAX",2614"SIM_IMUT2_TMIN",2615"SIM_IMUT3_ACC1_X",2616"SIM_IMUT3_ACC1_Y",2617"SIM_IMUT3_ACC1_Z",2618"SIM_IMUT3_ACC2_X",2619"SIM_IMUT3_ACC2_Y",2620"SIM_IMUT3_ACC2_Z",2621"SIM_IMUT3_ACC3_X",2622"SIM_IMUT3_ACC3_Y",2623"SIM_IMUT3_ACC3_Z",2624"SIM_IMUT3_ENABLE",2625"SIM_IMUT3_GYR1_X",2626"SIM_IMUT3_GYR1_Y",2627"SIM_IMUT3_GYR1_Z",2628"SIM_IMUT3_GYR2_X",2629"SIM_IMUT3_GYR2_Y",2630"SIM_IMUT3_GYR2_Z",2631"SIM_IMUT3_GYR3_X",2632"SIM_IMUT3_GYR3_Y",2633"SIM_IMUT3_GYR3_Z",2634"SIM_IMUT3_TMAX",2635"SIM_IMUT3_TMIN",2636"SIM_IMUT4_ACC1_X",2637"SIM_IMUT4_ACC1_Y",2638"SIM_IMUT4_ACC1_Z",2639"SIM_IMUT4_ACC2_X",2640"SIM_IMUT4_ACC2_Y",2641"SIM_IMUT4_ACC2_Z",2642"SIM_IMUT4_ACC3_X",2643"SIM_IMUT4_ACC3_Y",2644"SIM_IMUT4_ACC3_Z",2645"SIM_IMUT4_ENABLE",2646"SIM_IMUT4_GYR1_X",2647"SIM_IMUT4_GYR1_Y",2648"SIM_IMUT4_GYR1_Z",2649"SIM_IMUT4_GYR2_X",2650"SIM_IMUT4_GYR2_Y",2651"SIM_IMUT4_GYR2_Z",2652"SIM_IMUT4_GYR3_X",2653"SIM_IMUT4_GYR3_Y",2654"SIM_IMUT4_GYR3_Z",2655"SIM_IMUT4_TMAX",2656"SIM_IMUT4_TMIN",2657"SIM_IMUT5_ACC1_X",2658"SIM_IMUT5_ACC1_Y",2659"SIM_IMUT5_ACC1_Z",2660"SIM_IMUT5_ACC2_X",2661"SIM_IMUT5_ACC2_Y",2662"SIM_IMUT5_ACC2_Z",2663"SIM_IMUT5_ACC3_X",2664"SIM_IMUT5_ACC3_Y",2665"SIM_IMUT5_ACC3_Z",2666"SIM_IMUT5_ENABLE",2667"SIM_IMUT5_GYR1_X",2668"SIM_IMUT5_GYR1_Y",2669"SIM_IMUT5_GYR1_Z",2670"SIM_IMUT5_GYR2_X",2671"SIM_IMUT5_GYR2_Y",2672"SIM_IMUT5_GYR2_Z",2673"SIM_IMUT5_GYR3_X",2674"SIM_IMUT5_GYR3_Y",2675"SIM_IMUT5_GYR3_Z",2676"SIM_IMUT5_TMAX",2677"SIM_IMUT5_TMIN",2678"SIM_MAG2_DIA_X",2679"SIM_MAG2_DIA_Y",2680"SIM_MAG2_DIA_Z",2681"SIM_MAG2_ODI_X",2682"SIM_MAG2_ODI_Y",2683"SIM_MAG2_ODI_Z",2684"SIM_MAG2_OFS_X",2685"SIM_MAG2_OFS_Y",2686"SIM_MAG2_OFS_Z",2687"SIM_MAG3_DIA_X",2688"SIM_MAG3_DIA_Y",2689"SIM_MAG3_DIA_Z",2690"SIM_MAG3_ODI_X",2691"SIM_MAG3_ODI_Y",2692"SIM_MAG3_ODI_Z",2693"SIM_MAG3_OFS_X",2694"SIM_MAG3_OFS_Y",2695"SIM_MAG3_OFS_Z",2696"SIM_MAG_ALY_X",2697"SIM_MAG_ALY_Y",2698"SIM_MAG_ALY_Z",2699"SIM_MAG1_DIA_X",2700"SIM_MAG1_DIA_Y",2701"SIM_MAG1_DIA_Z",2702"SIM_MAG_MOT_X",2703"SIM_MAG_MOT_Y",2704"SIM_MAG_MOT_Z",2705"SIM_MAG1_ODI_X",2706"SIM_MAG1_ODI_Y",2707"SIM_MAG1_ODI_Z",2708"SIM_MAG1_OFS_X",2709"SIM_MAG1_OFS_Y",2710"SIM_MAG1_OFS_Z",2711"SIM_PARA_ENABLE",2712"SIM_PARA_PIN",2713"SIM_RICH_CTRL",2714"SIM_RICH_ENABLE",2715"SIM_SHIP_DSIZE",2716"SIM_SHIP_ENABLE",2717"SIM_SHIP_OFS_X",2718"SIM_SHIP_OFS_Y",2719"SIM_SHIP_OFS_Z",2720"SIM_SHIP_PSIZE",2721"SIM_SHIP_SPEED",2722"SIM_SHIP_SYSID",2723"SIM_TA_ENABLE",2724"SIM_VIB_FREQ_X",2725"SIM_VIB_FREQ_Y",2726"SIM_VIB_FREQ_Z",2727])27282729vinfo_key = self.vehicleinfo_key()2730if vinfo_key == "Rover":2731ret.update([2732])2733if vinfo_key == "ArduSub":2734ret.update([2735"SIM_BUOYANCY",2736])27372738return ret27392740def test_parameter_documentation_get_all_parameters(self):2741# this is a set of SIM_parameters which we know aren't currently2742# documented - but they really should be. We use this whitelist2743# to ensure any new SIM_ parameters added are documented2744sim_parameters_missing_documentation = self.get_sim_parameter_documentation_get_whitelist()27452746xml_filepath = os.path.join(self.buildlogs_dirpath(), "apm.pdef.xml")2747param_parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'param_metadata', 'param_parse.py')2748try:2749os.unlink(xml_filepath)2750except OSError:2751pass2752vehicle = self.log_name()2753if vehicle == "HeliCopter":2754vehicle = "ArduCopter"2755if vehicle == "QuadPlane":2756vehicle = "ArduPlane"2757cmd = [param_parse_filepath, '--vehicle', vehicle]2758# cmd.append("--verbose")2759if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:2760self.progress("Failed param_parse.py (%s)" % vehicle)2761return False2762htree = self.htree_from_xml(xml_filepath)27632764target_system = self.sysid_thismav()2765target_component = 127662767self.customise_SITL_commandline([2768"--unhide-groups"2769])27702771(parameters, seq_id) = self.download_parameters(target_system, target_component)27722773self.reset_SITL_commandline()27742775fail = False2776for param in parameters.keys():2777if param.startswith("SIM_"):2778if param in sim_parameters_missing_documentation:2779if param in htree:2780self.progress("%s is in both XML and whitelist; remove it from the whitelist" % param)2781fail = True2782# hopefully these get documented sometime....2783continue2784if param not in htree:2785self.progress("%s not in XML" % param)2786fail = True2787if fail:2788raise NotAchievedException("Downloaded parameters missing in XML")27892790self.progress("There are %u SIM_ parameters left to document" % len(sim_parameters_missing_documentation))27912792# FIXME: this should be doable if we filter out e.g BRD_* and CAN_*?2793# self.progress("Checking no extra parameters present in XML")2794# fail = False2795# for param in htree:2796# if param.startswith("SIM_"):2797# # too many of these to worry about2798# continue2799# if param not in parameters:2800# print("%s not in downloaded parameters but in XML" % param)2801# fail = True2802# if fail:2803# raise NotAchievedException("Extra parameters in XML")28042805def find_format_defines(self, lines):2806ret = {}2807for line in lines:2808if isinstance(line, bytes):2809line = line.decode("utf-8")2810m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)2811if m is None:2812continue2813(a, b) = (m.group(1), m.group(2))2814if a in ret:2815raise NotAchievedException("Duplicate define for (%s)" % a)2816ret[a] = b2817return ret28182819def vehicle_code_dirpath(self):2820'''returns path to vehicle-specific code directory e.g. ~/ardupilot/Rover'''2821dirname = self.log_name()2822if dirname == "QuadPlane":2823dirname = "ArduPlane"2824elif dirname == "HeliCopter":2825dirname = "ArduCopter"2826return os.path.join(self.rootdir(), dirname)28272828def find_LogStructureFiles(self):2829'''return list of files named LogStructure.h'''2830ret = []2831for root, _, files in os.walk(self.rootdir()):2832for f in files:2833if f == 'LogStructure.h':2834ret.append(os.path.join(root, f))2835if f == 'LogStructure_SBP.h':2836ret.append(os.path.join(root, f))2837return ret28382839def all_log_format_ids(self):2840'''parse C++ code to extract definitions of log messages'''2841structure_files = self.find_LogStructureFiles()2842structure_lines = []2843for f in structure_files:2844structure_lines.extend(open(f).readlines())28452846defines = self.find_format_defines(structure_lines)28472848ids = {}2849message_infos = []2850for f in structure_files:2851self.progress("structure file: %s" % f)2852state_outside = 02853state_inside = 12854state = state_outside28552856linestate_none = 452857linestate_within = 462858linestate = linestate_none2859debug = False2860if f == "/home/pbarker/rc/ardupilot/libraries/AP_HAL_ChibiOS/LogStructure.h":2861debug = True2862for line in open(f).readlines():2863if debug:2864print("line: %s" % line)2865if isinstance(line, bytes):2866line = line.decode("utf-8")2867line = re.sub("//.*", "", line) # trim comments2868if re.match(r"\s*$", line):2869# blank line2870continue2871if state == state_outside:2872if ("#define LOG_COMMON_STRUCTURES" in line or2873re.match("#define LOG_STRUCTURE_FROM_.*", line)):2874if debug:2875self.progress("Moving inside")2876state = state_inside2877continue2878if state == state_inside:2879if linestate == linestate_none:2880allowed_list = ['LOG_STRUCTURE_FROM_']28812882allowed = False2883for a in allowed_list:2884if a in line:2885allowed = True2886if allowed:2887continue2888m = re.match(r"\s*{(.*)},\s*", line)2889if m is not None:2890# complete line2891if debug:2892print("Complete line: %s" % str(line))2893message_infos.append(m.group(1))2894continue2895m = re.match(r"\s*{(.*)\\", line)2896if m is None:2897if debug:2898self.progress("Moving outside")2899state = state_outside2900continue2901partial_line = m.group(1)2902if debug:2903self.progress("partial line")2904linestate = linestate_within2905continue2906if linestate == linestate_within:2907if debug:2908self.progress("Looking for close-brace")2909m = re.match("(.*)}", line)2910if m is None:2911if debug:2912self.progress("no close-brace")2913line = line.rstrip()2914newline = re.sub(r"\\$", "", line)2915if newline == line:2916raise NotAchievedException("Expected backslash at end of line")2917line = newline2918line = line.rstrip()2919# cpp-style string concatenation:2920if debug:2921self.progress("more partial line")2922line = re.sub(r'"\s*"', '', line)2923partial_line += line2924continue2925if debug:2926self.progress("found close-brace")2927message_infos.append(partial_line + m.group(1))2928linestate = linestate_none2929continue2930raise NotAchievedException("Bad line (%s)")29312932if linestate != linestate_none:2933raise NotAchievedException("Must be linestate-none at end of file")29342935# now look in the vehicle-specific logfile:2936filepath = os.path.join(self.vehicle_code_dirpath(), "Log.cpp")2937state_outside = 672938state_inside = 682939state = state_outside2940linestate_none = 892941linestate_within = 902942linestate = linestate_none2943for line in open(filepath, 'rb').readlines():2944if isinstance(line, bytes):2945line = line.decode("utf-8")2946line = re.sub("//.*", "", line) # trim comments2947if re.match(r"\s*$", line):2948# blank line2949continue2950if state == state_outside:2951if ("const LogStructure" in line or2952"const struct LogStructure" in line):2953state = state_inside2954continue2955if state == state_inside:2956if re.match("};", line):2957state = state_outside2958break2959if linestate == linestate_none:2960if "#if HAL_QUADPLANE_ENABLED" in line:2961continue2962if "#if FRAME_CONFIG == HELI_FRAME" in line:2963continue2964if "#if AC_PRECLAND_ENABLED" in line:2965continue2966if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line:2967continue2968if "#end" in line:2969continue2970if "LOG_COMMON_STRUCTURES" in line:2971continue2972m = re.match(r"\s*{(.*)},\s*", line)2973if m is not None:2974# complete line2975# print("Complete line: %s" % str(line))2976message_infos.append(m.group(1))2977continue2978m = re.match(r"\s*{(.*)", line)2979if m is None:2980raise NotAchievedException("Bad line %s" % line)2981partial_line = m.group(1)2982linestate = linestate_within2983continue2984if linestate == linestate_within:2985m = re.match("(.*)}", line)2986if m is None:2987line = line.rstrip()2988newline = re.sub(r"\\$", "", line)2989if newline == line:2990raise NotAchievedException("Expected backslash at end of line")2991line = newline2992line = line.rstrip()2993# cpp-style string concatenation:2994line = re.sub(r'"\s*"', '', line)2995partial_line += line2996continue2997message_infos.append(partial_line + m.group(1))2998linestate = linestate_none2999continue3000raise NotAchievedException("Bad line (%s)")30013002if state == state_inside:3003raise NotAchievedException("Should not be in state_inside at end")30043005for message_info in message_infos:3006print("message_info: %s" % str(message_info))3007for define in defines:3008message_info = re.sub(define, defines[define], message_info)3009m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*(true|false))?\s*$', message_info) # noqa3010if m is None:3011print("NO MATCH")3012continue3013(name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5))3014if name in ids:3015raise NotAchievedException("Already seen a (%s) message" % name)3016ids[name] = {3017"name": name,3018"format": fmt,3019"labels": labels,3020"units": units,3021"multipliers": multipliers,3022}30233024# now look for Log_Write(...) messages:3025base_directories = [3026os.path.join(self.rootdir(), 'libraries'),3027self.vehicle_code_dirpath(),3028]3029log_write_statements = []3030for base_directory in base_directories:3031for root, dirs, files in os.walk(base_directory):3032state_outside = 373033state_inside = 383034state = state_outside3035for f in files:3036if not re.search("[.]cpp$", f):3037continue3038filepath = os.path.join(root, f)3039if "AP_Logger/examples" in filepath:3040# this is the sample file which contains examples...3041continue3042count = 03043for line in open(filepath, 'rb').readlines():3044if isinstance(line, bytes):3045line = line.decode("utf-8")3046if state == state_outside:3047if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or3048re.match(r"\s*logger[.]Write(?:Streaming)?\(", line)):3049state = state_inside3050line = re.sub("//.*", "", line) # trim comments3051log_write_statement = line3052continue3053if state == state_inside:3054line = re.sub("//.*", "", line) # trim comments3055# cpp-style string concatenation:3056line = re.sub(r'"\s*"', '', line)3057log_write_statement += line3058if re.match(r".*\);", line):3059log_write_statements.append(log_write_statement)3060state = state_outside3061count += 13062if state != state_outside:3063raise NotAchievedException("Expected to be outside at end of file")3064# print("%s has %u lines" % (f, count))3065# change all whitespace to single space3066log_write_statements = [re.sub(r"\s+", " ", x) for x in log_write_statements]3067# print("Got log-write-statements: %s" % str(log_write_statements))3068results = []3069for log_write_statement in log_write_statements:3070for define in defines:3071log_write_statement = re.sub(define, defines[define], log_write_statement)3072# fair warning: order is important here because of the3073# NKT/XKT special case below....3074my_re = r' logger[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'3075m = re.match(my_re, log_write_statement)3076if m is None:3077my_re = r' AP::logger\(\)[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'3078m = re.match(my_re, log_write_statement)3079if m is None:3080raise NotAchievedException("Did not match (%s) with (%s)" % (log_write_statement, str(my_re)))3081else:3082results.append((m.group(1), m.group(2)))30833084for result in results:3085(name, labels) = result3086if name in ids:3087raise Exception("Already have id for (%s)" % name)3088# self.progress("Adding Log_Write result (%s)" % name)3089ids[name] = {3090"name": name,3091"labels": labels,3092}30933094if len(ids) == 0:3095raise NotAchievedException("Did not get any ids")30963097return ids30983099def LoggerDocumentation(self):3100'''Test Onboard Logging Generation'''3101xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml")3102parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py')3103try:3104os.unlink(xml_filepath)3105except OSError:3106pass3107vehicle = self.log_name()3108if vehicle == 'BalanceBot':3109# same binary and parameters as Rover3110return3111vehicle_map = {3112"ArduCopter": "Copter",3113"HeliCopter": "Copter",3114"ArduPlane": "Plane",3115"QuadPlane": "Plane",3116"Rover": "Rover",3117"AntennaTracker": "Tracker",3118"ArduSub": "Sub",3119}3120vehicle = vehicle_map[vehicle]31213122cmd = [parse_filepath, '--vehicle', vehicle]3123# cmd.append("--verbose")3124if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:3125self.progress("Failed parse.py (%s)" % vehicle)3126return False3127length = os.path.getsize(xml_filepath)3128min_length = 10243129if length < min_length:3130raise NotAchievedException("short xml file (%u < %u)" %3131(length, min_length))3132self.progress("xml file length is %u" % length)31333134from lxml import objectify3135xml = open(xml_filepath, 'rb').read()3136objectify.enable_recursive_str()3137tree = objectify.fromstring(xml)31383139# we allow for no docs for replay messages, as these are not for end-users. They are3140# effectively binary blobs for replay3141REPLAY_MSGS = ['RFRH', 'RFRF', 'REV2', 'RSO2', 'RWA2', 'REV3', 'RSO3', 'RWA3', 'RMGI',3142'REY3', 'RFRN', 'RISH', 'RISI', 'RISJ', 'RBRH', 'RBRI', 'RRNH', 'RRNI',3143'RGPH', 'RGPI', 'RGPJ', 'RASH', 'RASI', 'RBCH', 'RBCI', 'RVOH', 'RMGH',3144'ROFH', 'REPH', 'REVH', 'RWOH', 'RBOH', 'RSLL']31453146docco_ids = {}3147for thing in tree.logformat:3148name = str(thing.get("name"))3149docco_ids[name] = {3150"name": name,3151"labels": [],3152}3153if getattr(thing.fields, 'field', None) is None:3154if name in REPLAY_MSGS:3155continue3156raise NotAchievedException("no doc fields for %s" % name)3157for field in thing.fields.field:3158# print("field: (%s)" % str(field))3159fieldname = field.get("name")3160# print("Got (%s.%s)" % (name,str(fieldname)))3161docco_ids[name]["labels"].append(fieldname)31623163code_ids = self.all_log_format_ids()3164# self.progress("Code ids: (%s)" % str(sorted(code_ids.keys())))3165# self.progress("Docco ids: (%s)" % str(sorted(docco_ids.keys())))31663167for name in sorted(code_ids.keys()):3168if name not in docco_ids:3169self.progress("Undocumented message: %s" % str(name))3170continue3171seen_labels = {}3172for label in code_ids[name]["labels"].split(","):3173if label in seen_labels:3174raise NotAchievedException("%s.%s is duplicate label" %3175(name, label))3176seen_labels[label] = True3177if label not in docco_ids[name]["labels"]:3178raise NotAchievedException("%s.%s not in documented fields (have (%s))" %3179(name, label, ",".join(docco_ids[name]["labels"])))3180missing = []3181for name in sorted(docco_ids):3182if name not in code_ids and name not in REPLAY_MSGS:3183missing.append(name)3184continue3185for label in docco_ids[name]["labels"]:3186if label not in code_ids[name]["labels"].split(","):3187# "name" was found in the XML, so was found in an3188# @LoggerMessage markup line, but was *NOT* found3189# in our bodgy parsing of the C++ code (in a3190# Log_Write call or in the static structures3191raise NotAchievedException("documented field %s.%s not found in code" %3192(name, label))3193if len(missing) > 0:3194raise NotAchievedException("Documented messages (%s) not in code" % missing)31953196def initialise_after_reboot_sitl(self):31973198# after reboot stream-rates may be zero. Request streams.3199self.drain_mav()3200self.wait_heartbeat()3201self.set_streamrate(self.sitl_streamrate())3202self.progress("Reboot complete")32033204def customise_SITL_commandline(self,3205customisations,3206model=None,3207defaults_filepath=None,3208wipe=False,3209set_streamrate_callback=None,3210binary=None):3211'''customisations could be "--serial5=sim:nmea" '''3212self.contexts[-1].sitl_commandline_customised = True3213self.mav.close()3214self.stop_SITL()3215self.start_SITL(binary=binary,3216model=model,3217defaults_filepath=defaults_filepath,3218customisations=customisations,3219wipe=wipe)3220self.mav.do_connect()3221tstart = time.time()3222while True:3223if time.time() - tstart > 30:3224raise NotAchievedException("Failed to customise")3225try:3226m = self.wait_heartbeat(drain_mav=True)3227if m.type == 0:3228self.progress("Bad heartbeat: %s" % str(m))3229continue3230except IOError:3231pass3232break3233if set_streamrate_callback is not None:3234set_streamrate_callback()3235else:3236self.set_streamrate(self.sitl_streamrate())3237m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=15)3238if m is None:3239raise NotAchievedException("No RC_CHANNELS message after restarting SITL")32403241# stash our arguments in case we need to preserve them in3242# reboot_sitl with Valgrind active:3243if self.valgrind or self.callgrind:3244self.valgrind_restart_model = model3245self.valgrind_restart_defaults_filepath = defaults_filepath3246self.valgrind_restart_customisations = customisations32473248def default_parameter_list(self):3249ret = {3250'LOG_DISARMED': 1,3251# also lower logging rate to reduce log sizes3252'LOG_DARM_RATEMAX': 5,3253'LOG_FILE_RATEMAX': 10,3254}3255if self.force_ahrs_type is not None:3256if self.force_ahrs_type == 2:3257ret["EK2_ENABLE"] = 13258if self.force_ahrs_type == 3:3259ret["EK3_ENABLE"] = 13260ret["AHRS_EKF_TYPE"] = self.force_ahrs_type3261if self.num_aux_imus > 0:3262ret["SIM_IMU_COUNT"] = self.num_aux_imus + 33263if self.replay:3264ret["LOG_REPLAY"] = 13265return ret32663267def apply_default_parameter_list(self):3268self.set_parameters(self.default_parameter_list())32693270def apply_default_parameters(self):3271self.apply_defaultfile_parameters()3272self.apply_default_parameter_list()3273self.reboot_sitl()32743275def reset_SITL_commandline(self):3276self.progress("Resetting SITL commandline to default")3277self.stop_SITL()3278try:3279del self.valgrind_restart_customisations3280except Exception:3281pass3282self.start_SITL(wipe=True)3283self.set_streamrate(self.sitl_streamrate())3284self.apply_default_parameters()3285self.progress("Reset SITL commandline to default")32863287def pause_SITL(self):3288'''temporarily stop the SITL process from running. Note that3289simulation time will not move forward!'''3290# self.progress("Pausing SITL")3291self.sitl.kill(signal.SIGSTOP)32923293def unpause_SITL(self):3294# self.progress("Unpausing SITL")3295self.sitl.kill(signal.SIGCONT)32963297def stop_SITL(self):3298self.progress("Stopping SITL")3299self.expect_list_remove(self.sitl)3300util.pexpect_close(self.sitl)3301self.sitl = None33023303def start_test(self, description):3304self.progress("##################################################################################")3305self.progress("########## %s ##########" % description)3306self.progress("##################################################################################")33073308def try_symlink_tlog(self):3309self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")3310self.progress("buildlog=%s" % self.buildlog)3311if os.path.exists(self.buildlog):3312os.unlink(self.buildlog)3313try:3314os.link(self.logfile, self.buildlog)3315except OSError as error:3316self.progress("OSError [%d]: %s" % (error.errno, error.strerror))3317self.progress("Problem: Failed to create link: %s => %s, "3318"will copy tlog manually to target location" %3319(self.logfile, self.buildlog))3320self.copy_tlog = True33213322#################################################3323# GENERAL UTILITIES3324#################################################3325def expect_list_clear(self):3326"""clear the expect list."""3327for p in self.expect_list[:]:3328self.expect_list.remove(p)33293330def expect_list_extend(self, list_to_add):3331"""Extend the expect list."""3332self.expect_list.extend(list_to_add)33333334def expect_list_add(self, item):3335"""Extend the expect list."""3336self.expect_list.extend([item])33373338def expect_list_remove(self, item):3339"""Remove item from the expect list."""3340self.expect_list.remove(item)33413342def heartbeat_interval_ms(self):3343c = self.context_get()3344if c is None:3345return 10003346return c.heartbeat_interval_ms33473348def set_heartbeat_interval_ms(self, interval_ms):3349c = self.context_get()3350if c is None:3351raise ValueError("No context")3352if c.original_heartbeat_interval_ms is None:3353c.original_heartbeat_interval_ms = c.heartbeat_interval_ms3354c.heartbeat_interval_ms = interval_ms33553356def set_heartbeat_rate(self, rate_hz):3357if rate_hz == 0:3358self.set_heartbeat_interval_ms(None)3359return3360self.set_heartbeat_interval_ms(1000.0/rate_hz)33613362def do_heartbeats(self, force=False):3363# self.progress("do_heartbeats")3364if self.heartbeat_interval_ms() is None and not force:3365return3366x = self.mav.messages.get("SYSTEM_TIME", None)3367now_wc = time.time()3368if (force or3369x is None or3370self.last_heartbeat_time_ms is None or3371self.last_heartbeat_time_ms < x.time_boot_ms or3372x.time_boot_ms - self.last_heartbeat_time_ms > self.heartbeat_interval_ms() or3373now_wc - self.last_heartbeat_time_wc_s > 1):3374if x is not None:3375self.last_heartbeat_time_ms = x.time_boot_ms3376self.last_heartbeat_time_wc_s = now_wc3377self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,3378mavutil.mavlink.MAV_AUTOPILOT_INVALID,33790,33800,33810)33823383def drain_all_pexpects(self):3384for p in self.expect_list:3385util.pexpect_drain(p)33863387def idle_hook(self, mav):3388"""Called when waiting for a mavlink message."""3389if self.in_drain_mav:3390return3391self.drain_all_pexpects()33923393class MessageHook():3394'''base class for objects that watch the message stream and check for3395validity of fields'''3396def __init__(self, suite):3397self.suite = suite33983399def process(self):3400pass34013402def progress_prefix(self):3403return ""34043405def progress(self, string):3406string = self.progress_prefix() + string3407self.suite.progress(string)34083409class ValidateIntPositionAgainstSimState(MessageHook):3410'''monitors a message containing a position containing lat/lng in 1e7,3411makes sure it stays close to SIMSTATE'''3412def __init__(self, suite, other_int_message_name, max_allowed_divergence=150):3413super(TestSuite.ValidateIntPositionAgainstSimState, self).__init__(suite)3414self.other_int_message_name = other_int_message_name3415self.max_allowed_divergence = max_allowed_divergence3416self.max_divergence = 03417self.gpi = None3418self.simstate = None3419self.last_print = 03420self.min_print_interval = 1 # seconds34213422def progress_prefix(self):3423return "VIPASS: "34243425def process(self, mav, m):3426if m.get_type() == self.other_int_message_name:3427self.gpi = m3428elif m.get_type() == 'SIMSTATE':3429self.simstate = m3430if self.gpi is None:3431return3432if self.simstate is None:3433return34343435divergence = self.suite.get_distance_int(self.gpi, self.simstate)3436if (time.time() - self.last_print > self.min_print_interval or3437divergence > self.max_divergence):3438self.progress(f"distance(SIMSTATE,{self.other_int_message_name})={divergence:.5f}m")3439self.last_print = time.time()3440if divergence > self.max_divergence:3441self.max_divergence = divergence3442if divergence > self.max_allowed_divergence:3443raise NotAchievedException(3444"%s diverged from simstate by %fm (max=%fm" %3445(self.other_int_message_name, divergence, self.max_allowed_divergence,))34463447def hook_removed(self):3448self.progress(f"Maximum divergence was {self.max_divergence}m (max={self.max_allowed_divergence}m)")34493450class ValidateGlobalPositionIntAgainstSimState(ValidateIntPositionAgainstSimState):3451def __init__(self, suite, **kwargs):3452super(TestSuite.ValidateGlobalPositionIntAgainstSimState, self).__init__(suite, 'GLOBAL_POSITION_INT', **kwargs)34533454class ValidateAHRS3AgainstSimState(ValidateIntPositionAgainstSimState):3455def __init__(self, suite, **kwargs):3456super(TestSuite.ValidateAHRS3AgainstSimState, self).__init__(suite, 'AHRS3', **kwargs)34573458def message_hook(self, mav, msg):3459"""Called as each mavlink msg is received."""3460# print("msg: %s" % str(msg))3461if msg.get_type() == 'STATUSTEXT':3462self.progress("AP: %s" % msg.text, send_statustext=False)34633464self.write_msg_to_tlog(msg)34653466self.idle_hook(mav)3467self.do_heartbeats()34683469for h in self.message_hooks:3470if isinstance(h, TestSuite.MessageHook):3471h.process(mav, msg)3472continue3473# assume it's a function3474h(mav, msg)34753476def send_message_hook(self, msg, x):3477self.write_msg_to_tlog(msg)34783479def write_msg_to_tlog(self, msg):3480usec = int(time.time() * 1.0e6)3481if self.tlog is None:3482tlog_filename = "autotest-%u.tlog" % usec3483self.tlog = open(tlog_filename, 'wb')34843485content = bytearray(struct.pack('>Q', usec) + msg.get_msgbuf())3486self.tlog.write(content)34873488def expect_callback(self, e):3489"""Called when waiting for a expect pattern."""3490for p in self.expect_list:3491if p == e:3492continue3493util.pexpect_drain(p)3494self.drain_mav(quiet=True)3495self.do_heartbeats()34963497def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False):3498'''drain all data on mavlink connection mav (defaulting to self.mav).3499It is assumed that this connection is connected to the normal3500simulation.'''3501if mav is None:3502mav = self.mav3503count = 03504tstart = time.time()3505self.pause_SITL()3506# sometimes we recv() when the process is likely to go away..3507old_autoreconnect = mav.autoreconnect3508mav.autoreconnect = False3509while True:3510try:3511this = mav.recv(1000000)3512except Exception:3513mav.autoreconnect = old_autoreconnect3514self.unpause_SITL()3515raise3516if len(this) == 0:3517break3518count += len(this)3519mav.autoreconnect = old_autoreconnect3520self.unpause_SITL()3521if quiet:3522return3523tdelta = time.time() - tstart3524if tdelta == 0:3525rate = "instantly"3526else:3527rate = "%f/s" % (count/float(tdelta),)3528self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate), send_statustext=False)3529if freshen_sim_time:3530self.get_sim_time()35313532def drain_mav(self, mav=None, unparsed=False, quiet=True):3533'''parse all data available on connection mav (defaulting to3534self.mav). It is assumed that mav is connected to the normal3535simulation'''3536if unparsed:3537return self.drain_mav_unparsed(quiet=quiet, mav=mav)3538if mav is None:3539mav = self.mav3540self.in_drain_mav = True3541count = 03542tstart = time.time()3543timeout = 1203544failed_to_drain = False3545self.pause_SITL()3546# sometimes we recv() when the process is likely to go away..3547old_autoreconnect = mav.autoreconnect3548mav.autoreconnect = False3549while True:3550try:3551receive_result = mav.recv_msg()3552except Exception:3553mav.autoreconnect = True3554self.unpause_SITL()3555raise3556if receive_result is None:3557break3558count += 13559if time.time() - tstart > timeout:3560# ArduPilot can produce messages faster than we can3561# consume them. Until a better solution is found,3562# just die if that seems to be the case:3563failed_to_drain = True3564quiet = False3565mav.autoreconnect = old_autoreconnect3566self.unpause_SITL()3567if quiet:3568self.in_drain_mav = False3569return3570tdelta = time.time() - tstart3571if tdelta == 0:3572rate = "instantly"3573else:3574rate = "%f/s" % (count/float(tdelta),)35753576if not quiet:3577self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False)35783579if failed_to_drain:3580raise NotAchievedException("Did not fully drain MAV within %ss" % timeout)35813582self.in_drain_mav = False35833584def do_timesync_roundtrip(self, quiet=False, timeout_in_wallclock=False):3585if not quiet:3586self.progress("Doing timesync roundtrip")3587if timeout_in_wallclock:3588tstart = time.time()3589else:3590tstart = self.get_sim_time()3591self.mav.mav.timesync_send(0, self.timesync_number * 1000 + self.mav.source_system)3592while True:3593if timeout_in_wallclock:3594now = time.time()3595else:3596now = self.get_sim_time_cached()3597if now - tstart > 5:3598raise AutoTestTimeoutException("Did not get timesync response")3599m = self.mav.recv_match(type='TIMESYNC', blocking=True, timeout=1)3600if not quiet:3601self.progress("Received: %s" % str(m))3602if m is None:3603continue3604if m.ts1 % 1000 != self.mav.source_system:3605self.progress("this isn't a response to our timesync (%s)" % (m.ts1 % 1000))3606continue3607if m.tc1 == 0:3608# this should also not happen:3609self.progress("this is a timesync request, which we don't answer")3610continue3611if int(m.ts1 / 1000) != self.timesync_number:3612self.progress("this isn't the one we just sent")3613continue3614if m.get_srcSystem() != self.mav.target_system:3615self.progress("response from system other than our target (want=%u got=%u" %3616(self.mav.target_system, m.get_srcSystem()))3617continue3618# no component check ATM because we send broadcast...3619# if m.get_srcComponent() != self.mav.target_component:3620# self.progress("response from component other than our target (got=%u want=%u)" % (m.get_srcComponent(), self.mav.target_component)) # noqa3621# continue3622if not quiet:3623self.progress("Received TIMESYNC response after %fs" % (now - tstart))3624self.timesync_number += 13625break36263627def log_filepath(self, lognum):3628'''return filepath to lognum (where lognum comes from LOG_ENTRY'''3629log_list = self.log_list()3630return log_list[lognum-1]36313632def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):3633tocheck = len(bytes1)3634if maxlen is not None:3635if tocheck > maxlen:3636tocheck = maxlen3637for i in range(0, tocheck):3638if bytes1[i] != bytes2[i]:3639raise NotAchievedException("differ at offset %u" % i)36403641def HIGH_LATENCY2(self):3642'''test sending of HIGH_LATENCY2'''36433644# set airspeed sensor type to DLVR for air temperature message testing3645if not self.is_plane():3646# Plane does not have enable parameter3647self.set_parameter("ARSPD_ENABLE", 1)3648self.set_parameter("ARSPD_BUS", 2)3649self.set_parameter("ARSPD_TYPE", 7)3650self.reboot_sitl()36513652self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True, verbose=True, timeout=30)36533654# should not be getting HIGH_LATENCY2 by default3655m = self.mav.recv_match(type='HIGH_LATENCY2', blocking=True, timeout=2)3656if m is not None:3657raise NotAchievedException("Shouldn't be getting HIGH_LATENCY2 by default")3658m = self.poll_message("HIGH_LATENCY2")3659if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:3660raise NotAchievedException("Expected GPS to be OK")3661self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)3662self.set_parameter("SIM_GPS1_TYPE", 0)3663self.delay_sim_time(10)3664self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)3665m = self.poll_message("HIGH_LATENCY2")3666self.progress(self.dump_message_verbose(m))3667if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) == 0:3668raise NotAchievedException("Expected GPS to be failed")36693670self.start_subtest("HIGH_LATENCY2 location")3671self.set_parameter("SIM_GPS1_TYPE", 1)3672self.delay_sim_time(10)3673m = self.poll_message("HIGH_LATENCY2")3674self.progress(self.dump_message_verbose(m))3675loc = mavutil.location(m.latitude, m.longitude, m.altitude, 0)3676dist = self.get_distance_int(loc, self.sim_location_int())36773678if dist > 1:3679raise NotAchievedException("Bad location from HIGH_LATENCY2")36803681self.start_subtest("HIGH_LATENCY2 Air Temperature")3682m = self.poll_message("HIGH_LATENCY2")3683mavutil.dump_message_verbose(sys.stdout, m)36843685if m.temperature_air == -128: # High_Latency2 defaults to INT8_MIN for no temperature available3686raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2")3687self.HIGH_LATENCY2_links()36883689def context_set_message_rate_hz(self, id, rate_hz, run_cmd=None):3690if run_cmd is None:3691run_cmd = self.run_cmd36923693overridden_message_rates = self.context_get().overridden_message_rates36943695if id not in overridden_message_rates:3696overridden_message_rates[id] = self.measure_message_rate(id)36973698self.set_message_rate_hz(id, rate_hz, run_cmd=run_cmd)36993700def HIGH_LATENCY2_links(self):37013702self.start_subtest("SerialProtocol_MAVLinkHL links")37033704ex = None3705self.context_push()3706mav2 = None3707try:37083709self.set_parameter("SERIAL2_PROTOCOL", 43) # HL)37103711self.reboot_sitl()37123713mav2 = mavutil.mavlink_connection(3714"tcp:localhost:%u" % self.adjust_ardupilot_port(5763),3715robust_parsing=True,3716source_system=7,3717source_component=7,3718)37193720self.start_subsubtest("Don't get HIGH_LATENCY2 by default")3721for mav in self.mav, mav2:3722self.assert_not_receive_message('HIGH_LATENCY2', mav=mav, timeout=10)37233724self.start_subsubtest("Get HIGH_LATENCY2 upon link enabled only on HL link")3725for run_cmd in self.run_cmd, self.run_cmd_int:3726self.run_cmd_enable_high_latency(True, run_cmd=run_cmd)3727self.assert_receive_message("HIGH_LATENCY2", mav=mav2, timeout=10)3728self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)37293730self.start_subsubtest("Not get HIGH_LATENCY2 upon HL disable")3731self.run_cmd_enable_high_latency(False, run_cmd=run_cmd)3732self.delay_sim_time(10)3733self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)3734self.drain_mav(mav2)3735self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)37363737self.start_subsubtest("Stream rate adjustments")3738self.run_cmd_enable_high_latency(True)3739self.assert_message_rate_hz("HIGH_LATENCY2", 0.2, ndigits=1, mav=mav2, sample_period=60)3740for test_rate in (1, 0.1, 2):3741self.test_rate(3742"HIGH_LATENCY2 on enabled link",3743test_rate,3744test_rate,3745mav=mav2,3746ndigits=1,3747victim_message="HIGH_LATENCY2",3748message_rate_sample_period=60,3749)3750self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)3751self.run_cmd_enable_high_latency(False)37523753self.start_subsubtest("Not get HIGH_LATENCY2 after disabling after playing with rates")3754self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)3755self.delay_sim_time(1)3756self.drain_mav(mav2)3757self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)37583759self.start_subsubtest("Enable and disable should not affect non-HL links getting HIGH_LATENCY2")3760self.set_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)3761self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)37623763self.run_cmd_enable_high_latency(True)3764self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav),37653766self.run_cmd_enable_high_latency(False)3767self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)3768except Exception as e:3769self.print_exception_caught(e)3770ex = e37713772self.context_pop()37733774self.reboot_sitl()37753776self.set_message_rate_hz("HIGH_LATENCY2", 0)37773778if ex is not None:3779raise ex37803781def download_full_log_list(self, print_logs=True):3782tstart = self.get_sim_time()3783self.mav.mav.log_request_list_send(self.sysid_thismav(),37841, # target component37850,37860xffff)3787logs = {}3788last_id = None3789num_logs = None3790while True:3791now = self.get_sim_time_cached()3792if now - tstart > 5:3793raise NotAchievedException("Did not download list")3794m = self.mav.recv_match(type='LOG_ENTRY',3795blocking=True,3796timeout=1)3797if print_logs:3798self.progress("Received (%s)" % str(m))3799if m is None:3800continue3801logs[m.id] = m3802if last_id is None:3803if m.num_logs == 0:3804# caller to guarantee this works:3805raise NotAchievedException("num_logs is zero")3806num_logs = m.num_logs3807else:3808if m.id != last_id + 1:3809raise NotAchievedException("Sequence not increasing")3810if m.num_logs != num_logs:3811raise NotAchievedException("Number of logs changed")3812if m.time_utc < 1000 and m.id != m.num_logs:3813raise NotAchievedException("Bad timestamp")3814if m.id != m.last_log_num:3815if m.size == 0:3816raise NotAchievedException("Zero-sized log")3817last_id = m.id3818if m.id == m.last_log_num:3819self.progress("Got all logs")3820break38213822# ensure we don't get any extras:3823m = self.mav.recv_match(type='LOG_ENTRY',3824blocking=True,3825timeout=2)3826if m is not None:3827raise NotAchievedException("Received extra LOG_ENTRY?!")3828return logs38293830def TestLogDownloadWrap(self):3831"""Test log wrapping."""3832if self.is_tracker():3833# tracker starts armed, which is annoying3834return3835self.progress("Ensuring we have contents we care about")3836self.set_parameter("LOG_FILE_DSRMROT", 1)3837self.set_parameter("LOG_DISARMED", 0)3838self.reboot_sitl()3839logspath = Path("logs")38403841def create_num_logs(num_logs, logsdir, clear_logsdir=True):3842if clear_logsdir:3843shutil.rmtree(logsdir, ignore_errors=True)3844logsdir.mkdir()3845lastlogfile_path = logsdir / Path("LASTLOG.TXT")3846self.progress(f"Add LASTLOG.TXT file with counter at {num_logs}")3847with open(lastlogfile_path, 'w') as lastlogfile:3848lastlogfile.write(f"{num_logs}\n")3849self.progress(f"Create fakelogs from 1 to {num_logs} on logs directory")3850for ii in range(1, num_logs + 1):3851new_log = logsdir / Path(f"{str(ii).zfill(8)}.BIN")3852with open(new_log, 'w+') as logfile:3853logfile.write(f"I AM LOG {ii}\n")3854logfile.write('1' * ii)38553856def verify_logs(test_log_num):3857try:3858wrap = False3859offset = 03860max_logs_num = int(self.get_parameter("LOG_MAX_FILES"))3861if test_log_num > max_logs_num:3862wrap = True3863offset = test_log_num - max_logs_num3864test_log_num = max_logs_num3865logs_dict = self.download_full_log_list(print_logs=False)3866if len(logs_dict) != test_log_num:3867raise NotAchievedException(3868f"Didn't get the full log list, expect {test_log_num} got {len(logs_dict)}")3869self.progress("Checking logs size are matching")3870start_log = offset if wrap else 13871for ii in range(start_log, test_log_num + 1 - offset):3872log_i = logspath / Path(f"{str(ii + offset).zfill(8)}.BIN")3873if logs_dict[ii].size != log_i.stat().st_size:3874logs_dict = self.download_full_log_list(print_logs=False)3875# sometimes we don't have finish writing the log, so get it again prevent failure3876if logs_dict[ii].size != log_i.stat().st_size:3877raise NotAchievedException(3878f"Log{ii} size mismatch : {logs_dict[ii].size} vs {log_i.stat().st_size}"3879)3880if wrap:3881self.progress("Checking wrapped logs size are matching")3882for ii in range(1, offset):3883log_i = logspath / Path(f"{str(ii).zfill(8)}.BIN")3884if logs_dict[test_log_num + 1 - offset + ii].size != log_i.stat().st_size:3885self.progress(f"{logs_dict[test_log_num + 1 - offset + ii]}")3886raise NotAchievedException(3887f"Log{test_log_num + 1 - offset + ii} size mismatch :"3888f" {logs_dict[test_log_num + 1 - offset + ii].size} vs {log_i.stat().st_size}"3889)3890except NotAchievedException as e:3891shutil.rmtree(logspath, ignore_errors=True)3892logspath.mkdir()3893with open(logspath / Path("LASTLOG.TXT"), 'w') as lastlogfile:3894lastlogfile.write("1\n")3895raise e38963897def add_and_verify_log(test_log_num):3898self.wait_ready_to_arm()3899self.arm_vehicle()3900self.delay_sim_time(1)3901self.disarm_vehicle()3902self.delay_sim_time(10)3903verify_logs(test_log_num + 1)39043905def create_and_verify_logs(test_log_num, clear_logsdir=True):3906self.progress(f"Test {test_log_num} logs")3907create_num_logs(test_log_num, logspath, clear_logsdir)3908self.reboot_sitl()3909verify_logs(test_log_num)3910self.start_subsubtest("Adding one more log")3911add_and_verify_log(test_log_num)39123913self.start_subtest("Checking log list match with filesystem info")3914create_and_verify_logs(500)3915create_and_verify_logs(10)3916create_and_verify_logs(1)39173918self.start_subtest("Change LOG_MAX_FILES and Checking log list match with filesystem info")3919self.set_parameter("LOG_MAX_FILES", 250)3920create_and_verify_logs(250)3921self.set_parameter("LOG_MAX_FILES", 1)3922create_and_verify_logs(1)39233924self.start_subtest("Change LOG_MAX_FILES, don't clear old logs and Checking log list match with filesystem info")3925self.set_parameter("LOG_MAX_FILES", 500)3926create_and_verify_logs(500)3927self.set_parameter("LOG_MAX_FILES", 250)3928create_and_verify_logs(250, clear_logsdir=False)39293930# cleanup3931shutil.rmtree(logspath, ignore_errors=True)39323933def TestLogDownload(self):3934"""Test Onboard Log Download."""3935if self.is_tracker():3936# tracker starts armed, which is annoying3937return3938self.progress("Ensuring we have contents we care about")3939self.set_parameter("LOG_FILE_DSRMROT", 1)3940self.set_parameter("LOG_DISARMED", 0)3941self.reboot_sitl()3942original_log_list = self.log_list()3943for i in range(0, 10):3944self.wait_ready_to_arm()3945self.arm_vehicle()3946self.delay_sim_time(1)3947self.disarm_vehicle()3948new_log_list = self.log_list()3949new_log_count = len(new_log_list) - len(original_log_list)3950if new_log_count != 10:3951raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" %3952(new_log_count, original_log_list, new_log_list))3953self.progress("Directory contents: %s" % str(new_log_list))39543955self.download_full_log_list()3956log_id = 53957ofs = 63958count = 23959self.start_subtest("downloading %u bytes from offset %u from log_id %u" %3960(count, ofs, log_id))3961self.mav.mav.log_request_data_send(self.sysid_thismav(),39621, # target component3963log_id,3964ofs,3965count)3966m = self.assert_receive_message('LOG_DATA', timeout=2)3967if m.ofs != ofs:3968raise NotAchievedException("Incorrect offset")3969if m.count != count:3970raise NotAchievedException("Did not get correct number of bytes")3971log_filepath = self.log_filepath(log_id)3972self.progress("Checking against log_filepath (%s)" % str(log_filepath))3973with open(log_filepath, "rb") as bob:3974bob.seek(ofs)3975actual_bytes = bob.read(2)3976actual_bytes = bytearray(actual_bytes)3977if m.data[0] != actual_bytes[0]:3978raise NotAchievedException("Bad first byte got=(0x%02x) want=(0x%02x)" %3979(m.data[0], actual_bytes[0]))3980if m.data[1] != actual_bytes[1]:3981raise NotAchievedException("Bad second byte")39823983log_id = 73984log_filepath = self.log_filepath(log_id)3985self.start_subtest("Downloading log id %u (%s)" % (log_id, log_filepath))3986with open(log_filepath, "rb") as bob:3987actual_bytes = bytearray(bob.read())39883989# get the size first3990self.mav.mav.log_request_list_send(self.sysid_thismav(),39911, # target component3992log_id,3993log_id)3994log_entry = self.assert_receive_message('LOG_ENTRY', timeout=2, verbose=True)3995if log_entry.size != len(actual_bytes):3996raise NotAchievedException("Incorrect bytecount")3997if log_entry.id != log_id:3998raise NotAchievedException("Incorrect log id received")39994000# download the log file in the normal way:4001bytes_to_fetch = 1000004002self.progress("Sending request for %u bytes at offset 0" % (bytes_to_fetch,))4003tstart = self.get_sim_time()4004self.mav.mav.log_request_data_send(4005self.sysid_thismav(),40061, # target component4007log_id,40080,4009bytes_to_fetch4010)4011bytes_to_read = bytes_to_fetch4012if log_entry.size < bytes_to_read:4013bytes_to_read = log_entry.size4014data_downloaded = []4015bytes_read = 04016last_print = 04017while True:4018if bytes_read >= bytes_to_read:4019break4020if self.get_sim_time_cached() - tstart > 120:4021raise NotAchievedException("Did not download log in good time")4022m = self.assert_receive_message('LOG_DATA', timeout=2)4023if m.ofs != bytes_read:4024raise NotAchievedException("Unexpected offset")4025if m.id != log_id:4026raise NotAchievedException("Unexpected id")4027if m.count == 0:4028raise NotAchievedException("Zero bytes read")4029data_downloaded.extend(m.data[0:m.count])4030bytes_read += m.count4031# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4032if time.time() - last_print > 10:4033last_print = time.time()4034self.progress("Read %u/%u" % (bytes_read, bytes_to_read))40354036self.progress("actual_bytes_len=%u data_downloaded_len=%u" %4037(len(actual_bytes), len(data_downloaded)))4038self.assert_bytes_equal(actual_bytes, data_downloaded, maxlen=bytes_to_read)40394040if False:4041bytes_to_read = log_entry.size4042bytes_read = 04043data_downloaded = []4044while bytes_read < bytes_to_read:4045bytes_to_fetch = int(random.random() * 100)4046if bytes_to_fetch > 90:4047bytes_to_fetch = 904048self.progress("Sending request for %u bytes at offset %u" % (bytes_to_fetch, bytes_read))4049self.mav.mav.log_request_data_send(4050self.sysid_thismav(),40511, # target component4052log_id,4053bytes_read,4054bytes_to_fetch4055)4056m = self.assert_receive_message('LOG_DATA', timeout=2)4057self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4058if m.ofs != bytes_read:4059raise NotAchievedException("Incorrect offset in reply want=%u got=%u (%s)" % (bytes_read, m.ofs, str(m)))4060stuff = m.data[0:m.count]4061data_downloaded.extend(stuff)4062bytes_read += m.count4063if len(data_downloaded) != bytes_read:4064raise NotAchievedException("extend fail")40654066if len(actual_bytes) != len(data_downloaded):4067raise NotAchievedException("Incorrect length: disk:%u downloaded: %u" %4068(len(actual_bytes), len(data_downloaded)))4069self.assert_bytes_equal(actual_bytes, data_downloaded)40704071self.start_subtest("Download log backwards")4072bytes_to_read = bytes_to_fetch4073if log_entry.size < bytes_to_read:4074bytes_to_read = log_entry.size4075bytes_read = 04076backwards_data_downloaded = []4077last_print = 04078while bytes_read < bytes_to_read:4079bytes_to_fetch = int(random.random() * 99) + 14080if bytes_to_fetch > 90:4081bytes_to_fetch = 904082if bytes_to_fetch > bytes_to_read - bytes_read:4083bytes_to_fetch = bytes_to_read - bytes_read4084ofs = bytes_to_read - bytes_read - bytes_to_fetch4085# self.progress("bytes_to_read=%u bytes_read=%u bytes_to_fetch=%u ofs=%d" %4086# (bytes_to_read, bytes_read, bytes_to_fetch, ofs))4087self.mav.mav.log_request_data_send(4088self.sysid_thismav(),40891, # target component4090log_id,4091ofs,4092bytes_to_fetch4093)4094m = self.assert_receive_message('LOG_DATA', timeout=2)4095if m.count == 0:4096raise NotAchievedException("xZero bytes read (ofs=%u)" % (ofs,))4097if m.count > bytes_to_fetch:4098raise NotAchievedException("Read too many bytes?!")4099stuff = m.data[0:m.count]4100stuff.extend(backwards_data_downloaded)4101backwards_data_downloaded = stuff4102bytes_read += m.count4103# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4104if time.time() - last_print > 10:4105last_print = time.time()4106self.progress("xRead %u/%u" % (bytes_read, bytes_to_read))41074108self.assert_bytes_equal(actual_bytes, backwards_data_downloaded, maxlen=bytes_to_read)4109# if len(actual_bytes) != len(backwards_data_downloaded):4110# raise NotAchievedException("Size delta: actual=%u vs downloaded=%u" %4111# (len(actual_bytes), len(backwards_data_downloaded)))41124113def download_log(self, log_id, timeout=360):4114tstart = self.get_sim_time()4115data_downloaded = []4116bytes_read = 04117last_print = 04118while True:4119if self.get_sim_time_cached() - tstart > timeout:4120raise NotAchievedException("Did not download log in good time")4121self.mav.mav.log_request_data_send(4122self.sysid_thismav(),41231, # target component4124log_id,4125bytes_read,4126904127)4128m = self.assert_receive_message('LOG_DATA', timeout=2)4129if m.ofs != bytes_read:4130raise NotAchievedException(f"Unexpected offset {bytes_read=} {self.dump_message_verbose(m)}")4131if m.id != log_id:4132raise NotAchievedException(f"Unexpected id {log_id=} {self.dump_message_verbose(m)}")4133data_downloaded.extend(m.data[0:m.count])4134bytes_read += m.count4135if m.count < 90: # FIXME: constant4136break4137# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4138if time.time() - last_print > 10:4139last_print = time.time()4140self.progress(f"{bytes_read=}")4141return data_downloaded41424143def TestLogDownloadLogRestart(self):4144'''test logging restarts after log download'''4145# self.delay_sim_time(30)4146self.set_parameters({4147"LOG_FILE_RATEMAX": 1,4148})4149self.reboot_sitl()4150number = self.current_onboard_log_number()4151content = self.download_log(number)4152print(f"Content is of length {len(content)}")4153# current_log_filepath = self.current_onboard_log_filepath()4154self.delay_sim_time(5)4155new_number = self.current_onboard_log_number()4156if number == new_number:4157raise NotAchievedException("Did not start logging again")4158new_content = self.download_log(new_number)4159if len(new_content) == 0:4160raise NotAchievedException(f"Unexpected length {len(new_content)=}")41614162#################################################4163# SIM UTILITIES4164#################################################4165def get_sim_time(self, timeout=60, drain_mav=True):4166"""Get SITL time in seconds."""4167if drain_mav:4168self.drain_mav()4169tstart = time.time()4170while True:4171self.drain_all_pexpects()4172if time.time() - tstart > timeout:4173raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)41744175m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=0.1)4176if m is None:4177continue41784179return m.time_boot_ms * 1.0e-341804181def get_sim_time_cached(self):4182"""Get SITL time in seconds."""4183x = self.mav.messages.get("SYSTEM_TIME", None)4184if x is None:4185raise NotAchievedException("No cached time available (%s)" % (self.mav.sysid,))4186ret = x.time_boot_ms * 1.0e-34187if ret != self.last_sim_time_cached:4188self.last_sim_time_cached = ret4189self.last_sim_time_cached_wallclock = time.time()4190else:4191timeout = 304192if self.valgrind:4193timeout *= 104194if time.time() - self.last_sim_time_cached_wallclock > timeout and not self.gdb:4195raise AutoTestTimeoutException("sim_time_cached is not updating!")4196return ret41974198def sim_location(self):4199"""Return current simulator location."""4200m = self.mav.recv_match(type='SIMSTATE', blocking=True)4201return mavutil.location(m.lat*1.0e-7,4202m.lng*1.0e-7,42030,4204math.degrees(m.yaw))42054206def sim_location_int(self):4207"""Return current simulator location."""4208m = self.mav.recv_match(type='SIMSTATE', blocking=True)4209return mavutil.location(m.lat,4210m.lng,42110,4212math.degrees(m.yaw))42134214def save_wp(self, ch=7):4215"""Trigger RC Aux to save waypoint."""4216self.set_rc(ch, 1000)4217self.delay_sim_time(1)4218self.set_rc(ch, 2000)4219self.delay_sim_time(1)4220self.set_rc(ch, 1000)4221self.delay_sim_time(1)42224223def correct_wp_seq_numbers(self, wps):4224# renumber the items:4225count = 04226for item in wps:4227item.seq = count4228count += 142294230def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1):4231'''takes a list of (type, n, e, alt) items. Creates a mission in4232absolute frame using alt as relative-to-home and n and e as4233offsets in metres from home'''42344235# add a dummy waypoint for home4236items = [(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0)]4237items.extend(items_in)4238seq = 04239ret = []4240for item in items:4241if not isinstance(item, tuple):4242# hope this is a mission item...4243item.seq = seq4244seq += 14245ret.append(item)4246continue4247opts = {}4248try:4249(t, n, e, alt, opts) = item4250except ValueError:4251(t, n, e, alt) = item4252lat = 04253lng = 04254if n != 0 or e != 0:4255loc = self.home_relative_loc_ne(n, e)4256lat = loc.lat4257lng = loc.lng4258frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT4259if not self.ardupilot_stores_frame_for_cmd(t):4260frame = mavutil.mavlink.MAV_FRAME_GLOBAL4261if opts.get('frame', None) is not None:4262frame = opts.get('frame')4263ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, x=int(lat*1e7), y=int(lng*1e7), z=alt))4264seq += 142654266return ret42674268def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):4269mission = self.create_simple_relhome_mission(4270items,4271target_system=target_system,4272target_component=target_component)4273self.check_mission_upload_download(mission)42744275def get_mission_count(self):4276return self.get_parameter("MIS_TOTAL")42774278def run_auxfunc(self,4279function,4280level,4281run_cmd=None,4282want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):4283if run_cmd is None:4284run_cmd = self.run_cmd4285run_cmd(4286mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,4287p1=function,4288p2=level,4289want_result=want_result,4290)42914292def assert_mission_count(self, expected):4293count = self.get_mission_count()4294if count != expected:4295raise NotAchievedException("Unexpected count got=%u want=%u" %4296(count, expected))42974298def clear_wp(self, ch=8):4299"""Trigger RC Aux to clear waypoint."""4300self.progress("Clearing waypoints")4301self.set_rc(ch, 1000)4302self.delay_sim_time(0.5)4303self.set_rc(ch, 2000)4304self.delay_sim_time(0.5)4305self.set_rc(ch, 1000)4306self.assert_mission_count(0)43074308def log_list(self):4309'''return a list of log files present in POSIX-style loging dir'''4310ret = sorted(glob.glob("logs/00*.BIN"))4311self.progress("log list: %s" % str(ret))4312return ret43134314def assert_parameter_values(self, parameters, epsilon=None):4315names = parameters.keys()4316got = self.get_parameters(names)4317for name in names:4318equal = got[name] == parameters[name]4319if epsilon is not None:4320delta = abs(got[name] - parameters[name])4321equal = delta <= epsilon4322if not equal:4323raise NotAchievedException("parameter %s want=%f got=%f" %4324(name, parameters[name], got[name]))4325self.progress("%s has expected value %f" % (name, got[name]))43264327def assert_parameter_value(self, parameter, required, **kwargs):4328self.assert_parameter_values({4329parameter: required,4330}, **kwargs)43314332def assert_reach_imu_temperature(self, target, timeout):4333'''wait to reach a target temperature'''4334tstart = self.get_sim_time()4335temp_ok = False4336last_print_temp = -1004337while self.get_sim_time_cached() - tstart < timeout:4338m = self.assert_receive_message('RAW_IMU', timeout=2)4339temperature = m.temperature*0.014340if temperature >= target:4341self.progress("Reached temperature %.1f" % temperature)4342temp_ok = True4343break4344if temperature - last_print_temp > 1:4345self.progress("temperature %.1f" % temperature)4346last_print_temp = temperature43474348if not temp_ok:4349raise NotAchievedException("target temperature")43504351def message_has_field_values_field_values_equal(self, fieldname, value, got, epsilon=None):4352if isinstance(value, float):4353if math.isnan(value) or math.isnan(got):4354return math.isnan(value) and math.isnan(got)43554356if type(value) is not str and epsilon is not None:4357return abs(got - value) <= epsilon43584359return got == value43604361def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None):4362for (fieldname, value) in fieldvalues.items():4363if "[" in fieldname: # fieldname == "arrayname[index]"4364assert fieldname[-1] == "]", fieldname4365arrayname, index = fieldname.split("[", 1)4366index = int(index[:-1])4367got = getattr(m, arrayname)[index]4368else:4369got = getattr(m, fieldname)43704371value_string = value4372got_string = got4373enum_name = m.fieldenums_by_name.get(fieldname, None)4374if enum_name is not None:4375enum = mavutil.mavlink.enums[enum_name]4376if value not in enum:4377raise ValueError("Expected value %s not in enum %s" % (value, enum_name))4378if got not in enum:4379raise ValueError("Received value %s not in enum %s" % (value, enum_name))4380value_string = "%s (%s)" % (value, enum[value].name)4381got_string = "%s (%s)" % (got, enum[got].name)43824383if not self.message_has_field_values_field_values_equal(4384fieldname, value, got, epsilon=epsilon4385):4386# see if this is an enumerated field:4387self.progress(self.dump_message_verbose(m))4388self.progress("Expected %s.%s to be %s, got %s" %4389(m.get_type(), fieldname, value_string, got_string))4390return False4391if verbose:4392self.progress("%s.%s has expected value %s" %4393(m.get_type(), fieldname, value_string))4394return True43954396def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):4397if self.message_has_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon):4398return4399raise NotAchievedException("Did not get expected field values")44004401def assert_cached_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None):4402'''checks the most-recently received instance of message to ensure it4403has the correct field values'''4404m = self.get_cached_message(message)4405self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)4406return m44074408def assert_received_message_field_values(self,4409message,4410fieldvalues,4411verbose=True,4412very_verbose=False,4413epsilon=None,4414poll=False,4415timeout=None,4416check_context=False,4417):4418if poll:4419self.poll_message(message)4420m = self.assert_receive_message(4421message,4422verbose=verbose,4423very_verbose=very_verbose,4424timeout=timeout,4425check_context=check_context4426)4427self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)4428return m44294430# FIXME: try to use wait_and_maintain here?4431def wait_message_field_values(self,4432message,4433fieldvalues,4434timeout=10,4435epsilon=None,4436instance=None,4437minimum_duration=None,4438verbose=False,4439very_verbose=False,4440):44414442tstart = self.get_sim_time_cached()4443pass_start = None4444last_debug = 04445while True:4446now = self.get_sim_time_cached()4447if now - tstart > timeout:4448raise NotAchievedException("Field never reached values")4449m = self.assert_receive_message(4450message,4451instance=instance,4452verbose=verbose,4453very_verbose=very_verbose,4454)4455if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose):4456if minimum_duration is not None:4457if pass_start is None:4458pass_start = now4459continue4460delta = now - pass_start4461if now - last_debug >= 1:4462last_debug = now4463self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)")4464if delta < minimum_duration:4465continue4466else:4467self.progress("Reached field values")4468return m4469pass_start = None44704471def onboard_logging_not_log_disarmed(self):4472self.start_subtest("Test LOG_DISARMED-is-false behaviour")4473self.set_parameter("LOG_DISARMED", 0)4474self.set_parameter("LOG_FILE_DSRMROT", 0)4475self.reboot_sitl()4476self.wait_ready_to_arm() # let things setttle4477self.start_subtest("Ensure setting LOG_DISARMED yields a new file")4478original_list = self.log_list()4479self.progress("original list: %s" % str(original_list))4480self.set_parameter("LOG_DISARMED", 1)4481self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4482new_list = self.log_list()4483self.progress("new list: %s" % str(new_list))4484if len(new_list) - len(original_list) != 1:4485raise NotAchievedException("Got more than one new log")4486self.set_parameter("LOG_DISARMED", 0)4487self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4488new_list = self.log_list()4489if len(new_list) - len(original_list) != 1:4490raise NotAchievedException("Got more or less than one new log after toggling LOG_DISARMED off")44914492self.start_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")4493self.set_parameter("LOG_DISARMED", 1)4494self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4495new_new_list = self.log_list()4496if len(new_new_list) != len(new_list):4497raise NotAchievedException("Got extra files when toggling LOG_DISARMED")4498self.set_parameter("LOG_DISARMED", 0)4499self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4500new_new_list = self.log_list()4501if len(new_new_list) != len(new_list):4502raise NotAchievedException("Got extra files when toggling LOG_DISARMED to 0 again")4503self.end_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")45044505self.start_subtest("Check disarm rot when log disarmed is zero")4506self.assert_parameter_value("LOG_DISARMED", 0)4507self.set_parameter("LOG_FILE_DSRMROT", 1)4508old_speedup = self.get_parameter("SIM_SPEEDUP")4509# reduce speedup to reduce chance of race condition here4510self.set_parameter("SIM_SPEEDUP", 1)4511pre_armed_list = self.log_list()4512if self.is_copter() or self.is_heli():4513self.set_parameter("DISARM_DELAY", 0)4514self.arm_vehicle()4515post_armed_list = self.log_list()4516if len(post_armed_list) != len(pre_armed_list):4517raise NotAchievedException("Got unexpected new log")4518self.disarm_vehicle()4519old_speedup = self.set_parameter("SIM_SPEEDUP", old_speedup)4520post_disarmed_list = self.log_list()4521if len(post_disarmed_list) != len(post_armed_list):4522raise NotAchievedException("Log rotated immediately")4523self.progress("Allowing time for post-disarm-logging to occur if it will")4524self.delay_sim_time(5)4525post_disarmed_post_delay_list = self.log_list()4526if len(post_disarmed_post_delay_list) != len(post_disarmed_list):4527raise NotAchievedException("Got log rotation when we shouldn't have")4528self.progress("Checking that arming does produce a new log")4529self.arm_vehicle()4530post_armed_list = self.log_list()4531if len(post_armed_list) - len(post_disarmed_post_delay_list) != 1:4532raise NotAchievedException("Did not get new log for rotation")4533self.progress("Now checking natural rotation after HAL_LOGGER_ARM_PERSIST")4534self.disarm_vehicle()4535post_disarmed_list = self.log_list()4536if len(post_disarmed_list) != len(post_armed_list):4537raise NotAchievedException("Log rotated immediately")4538self.delay_sim_time(30)4539delayed_post_disarmed_list = self.log_list()4540# should *still* not get another log as LOG_DISARMED is false4541if len(post_disarmed_list) != len(delayed_post_disarmed_list):4542self.progress("Unexpected new log found")45434544def onboard_logging_log_disarmed(self):4545self.start_subtest("Test LOG_DISARMED-is-true behaviour")4546start_list = self.log_list()4547self.set_parameter("LOG_FILE_DSRMROT", 0)4548self.set_parameter("LOG_DISARMED", 0)4549self.reboot_sitl()4550restart_list = self.log_list()4551if len(start_list) != len(restart_list):4552raise NotAchievedException(4553"Unexpected log detected (pre-delay) initial=(%s) restart=(%s)" %4554(str(sorted(start_list)), str(sorted(restart_list))))4555self.delay_sim_time(20)4556restart_list = self.log_list()4557if len(start_list) != len(restart_list):4558raise NotAchievedException("Unexpected log detected (post-delay)")4559self.set_parameter("LOG_DISARMED", 1)4560self.delay_sim_time(5) # LOG_DISARMED is polled4561post_log_disarmed_set_list = self.log_list()4562if len(post_log_disarmed_set_list) == len(restart_list):4563raise NotAchievedException("Did not get new log when LOG_DISARMED set")4564self.progress("Ensuring we get a new log after a reboot")4565self.reboot_sitl()4566self.delay_sim_time(5)4567post_reboot_log_list = self.log_list()4568if len(post_reboot_log_list) == len(post_log_disarmed_set_list):4569raise NotAchievedException("Did not get fresh log-disarmed log after a reboot")4570self.progress("Ensuring no log rotation when we toggle LOG_DISARMED off then on again")4571self.set_parameter("LOG_DISARMED", 0)4572current_log_filepath = self.current_onboard_log_filepath()4573self.delay_sim_time(10) # LOG_DISARMED is polled4574post_toggleoff_list = self.log_list()4575if len(post_toggleoff_list) != len(post_reboot_log_list):4576raise NotAchievedException("Shouldn't get new file yet")4577self.progress("Ensuring log does not grow when LOG_DISARMED unset...")4578current_log_filepath_size = os.path.getsize(current_log_filepath)4579self.delay_sim_time(5)4580current_log_filepath_new_size = os.path.getsize(current_log_filepath)4581if current_log_filepath_new_size != current_log_filepath_size:4582raise NotAchievedException(4583"File growing after LOG_DISARMED unset (new=%u old=%u" %4584(current_log_filepath_new_size, current_log_filepath_size))4585self.progress("Turning LOG_DISARMED back on again")4586self.set_parameter("LOG_DISARMED", 1)4587self.delay_sim_time(5) # LOG_DISARMED is polled4588post_toggleon_list = self.log_list()4589if len(post_toggleon_list) != len(post_toggleoff_list):4590raise NotAchievedException("Log rotated when it shouldn't")4591self.progress("Checking log is now growing again")4592if os.path.getsize(current_log_filepath) == current_log_filepath_size:4593raise NotAchievedException("Log is not growing")45944595# self.progress("Checking LOG_FILE_DSRMROT behaviour when log_DISARMED set")4596# self.set_parameter("LOG_FILE_DSRMROT", 1)4597# self.wait_ready_to_arm()4598# pre = self.log_list()4599# self.arm_vehicle()4600# post = self.log_list()4601# if len(pre) != len(post):4602# raise NotAchievedException("Rotation happened on arming?!")4603# size_a = os.path.getsize(current_log_filepath)4604# self.delay_sim_time(5)4605# size_b = os.path.getsize(current_log_filepath)4606# if size_b <= size_a:4607# raise NotAchievedException("Log not growing")4608# self.disarm_vehicle()4609# instant_post_disarm_list = self.log_list()4610# self.progress("Should not rotate straight away")4611# if len(instant_post_disarm_list) != len(post):4612# raise NotAchievedException("Should not rotate straight away")4613# self.delay_sim_time(20)4614# post_disarm_list = self.log_list()4615# if len(post_disarm_list) - len(instant_post_disarm_list) != 1:4616# raise NotAchievedException("Did not get exactly one more log")46174618# self.progress("If we re-arm during the HAL_LOGGER_ARM_PERSIST period it should rotate")46194620def onboard_logging_forced_arm(self):4621'''ensure a bug where we didn't start logging when arming was forced4622does not reappear'''4623self.start_subtest("Ensure we get a log when force-arming")4624self.set_parameter("LOG_DISARMED", 0)4625self.reboot_sitl() # so we'll definitely start a log on arming4626pre_arming_list = self.log_list()4627self.wait_ready_to_arm()4628self.arm_vehicle(force=True)4629# we might be relying on a thread to actually create the log4630# file when doing forced-arming; give the file time to appear:4631self.delay_sim_time(10)4632post_arming_list = self.log_list()4633self.disarm_vehicle()4634if len(post_arming_list) <= len(pre_arming_list):4635raise NotAchievedException("Did not get a log on forced arm")46364637def Logging(self):4638'''Test Onboard Logging'''4639if self.is_tracker():4640return4641self.onboard_logging_forced_arm()4642self.onboard_logging_log_disarmed()4643self.onboard_logging_not_log_disarmed()46444645def LoggingFormatSanityChecks(self, path):4646dfreader = self.dfreader_for_path(path)4647first_message = dfreader.recv_match()4648if first_message.get_type() != 'FMT':4649raise NotAchievedException("Expected first message to be a FMT message")4650if first_message.Name != 'FMT':4651raise NotAchievedException("Expected first message to be the FMT FMT message")46524653self.progress("Ensuring DCM format is received") # it's a WriteStreaming message...4654while True:4655m = dfreader.recv_match(type='FMT')4656if m is None:4657raise NotAchievedException("Did not find DCM format")4658if m.Name != 'DCM':4659continue4660self.progress("Found DCM format")4661break46624663self.progress("No message should appear before its format")4664dfreader.rewind()4665seen_formats = set()4666while True:4667m = dfreader.recv_match()4668if m is None:4669break4670m_type = m.get_type()4671if m_type == 'FMT':4672seen_formats.add(m.Name)4673continue4674if m_type not in seen_formats:4675raise ValueError(f"{m_type} seen before its format")4676# print(f"{m_type} OK")46774678def LoggingFormat(self):4679'''ensure formats are emmitted appropriately'''46804681self.context_push()4682self.set_parameter('LOG_FILE_DSRMROT', 1)4683self.wait_ready_to_arm()4684for i in range(3):4685self.arm_vehicle()4686self.delay_sim_time(5)4687path = self.current_onboard_log_filepath()4688self.disarm_vehicle()4689self.LoggingFormatSanityChecks(path)4690self.context_pop()46914692self.context_push()4693for i in range(3):4694self.set_parameter("LOG_DISARMED", 1)4695self.reboot_sitl()4696self.delay_sim_time(5)4697path = self.current_onboard_log_filepath()4698self.set_parameter("LOG_DISARMED", 0)4699self.LoggingFormatSanityChecks(path)4700self.context_pop()47014702def TestLogDownloadMAVProxy(self, upload_logs=False):4703"""Download latest log."""4704filename = "MAVProxy-downloaded-log.BIN"4705mavproxy = self.start_mavproxy()4706self.mavproxy_load_module(mavproxy, 'log')4707self.set_parameter('SIM_SPEEDUP', 1)4708mavproxy.send("log list\n")4709mavproxy.expect("numLogs")4710self.wait_heartbeat()4711self.wait_heartbeat()4712mavproxy.send("set shownoise 0\n")4713mavproxy.send("log download latest %s\n" % filename)4714mavproxy.expect("Finished downloading", timeout=120)4715self.mavproxy_unload_module(mavproxy, 'log')4716self.stop_mavproxy(mavproxy)47174718def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):4719"""Download latest log over network port"""4720self.context_push()4721self.set_parameters({4722"NET_ENABLE": 1,4723"LOG_DISARMED": 0,4724"LOG_DARM_RATEMAX": 1, # make small logs4725# UDP client4726"NET_P1_TYPE": 1,4727"NET_P1_PROTOCOL": 2,4728"NET_P1_PORT": 16001,4729"NET_P1_IP0": 127,4730"NET_P1_IP1": 0,4731"NET_P1_IP2": 0,4732"NET_P1_IP3": 1,4733# UDP server4734"NET_P2_TYPE": 2,4735"NET_P2_PROTOCOL": 2,4736"NET_P2_PORT": 16002,4737"NET_P2_IP0": 0,4738"NET_P2_IP1": 0,4739"NET_P2_IP2": 0,4740"NET_P2_IP3": 0,4741# TCP client4742"NET_P3_TYPE": 3,4743"NET_P3_PROTOCOL": 2,4744"NET_P3_PORT": 16003,4745"NET_P3_IP0": 127,4746"NET_P3_IP1": 0,4747"NET_P3_IP2": 0,4748"NET_P3_IP3": 1,4749# TCP server4750"NET_P4_TYPE": 4,4751"NET_P4_PROTOCOL": 2,4752"NET_P4_PORT": 16004,4753"NET_P4_IP0": 0,4754"NET_P4_IP1": 0,4755"NET_P4_IP2": 0,4756"NET_P4_IP3": 0,4757})4758self.reboot_sitl()47594760# ensure the latest log file is very small:4761self.context_push()4762self.set_parameter('LOG_DISARMED', 1)4763self.delay_sim_time(15)4764self.progress(f"Current onboard log filepath {self.current_onboard_log_filepath()}")4765self.context_pop()47664767# ensure that the autopilot has a timestamp on that file by4768# now, or MAVProxy does not see it as the latest log:4769self.wait_gps_fix_type_gte(3)47704771self.set_parameter('SIM_SPEEDUP', 1)47724773endpoints = [('UDPClient', ':16001') ,4774('UDPServer', 'udpout:127.0.0.1:16002'),4775('TCPClient', 'tcpin:0.0.0.0:16003'),4776('TCPServer', 'tcp:127.0.0.1:16004')]4777for name, e in endpoints:4778self.progress("Downloading log with %s %s" % (name, e))4779filename = "MAVProxy-downloaded-net-log-%s.BIN" % name47804781mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])4782self.mavproxy_load_module(mavproxy, 'log')4783self.wait_heartbeat()4784mavproxy.send("log list\n")4785mavproxy.expect("numLogs")4786# ensure the full list of logs has come out4787for i in range(5):4788self.wait_heartbeat()4789mavproxy.send("log download latest %s\n" % filename)4790mavproxy.expect("Finished downloading", timeout=120)4791self.mavproxy_unload_module(mavproxy, 'log')4792self.stop_mavproxy(mavproxy)47934794self.set_parameters({4795# multicast UDP client4796"NET_P1_TYPE": 1,4797"NET_P1_PROTOCOL": 2,4798"NET_P1_PORT": 16005,4799"NET_P1_IP0": 239,4800"NET_P1_IP1": 255,4801"NET_P1_IP2": 145,4802"NET_P1_IP3": 50,4803# Broadcast UDP client4804"NET_P2_TYPE": 1,4805"NET_P2_PROTOCOL": 2,4806"NET_P2_PORT": 16006,4807"NET_P2_IP0": 255,4808"NET_P2_IP1": 255,4809"NET_P2_IP2": 255,4810"NET_P2_IP3": 255,4811"NET_P3_TYPE": -1,4812"NET_P4_TYPE": -1,4813"LOG_DISARMED": 0,4814})4815self.reboot_sitl()48164817self.set_parameter('SIM_SPEEDUP', 1)48184819endpoints = [('UDPMulticast', 'mcast:16005') ,4820('UDPBroadcast', ':16006')]4821for name, e in endpoints:4822self.progress("Downloading log with %s %s" % (name, e))4823filename = "MAVProxy-downloaded-net-log-%s.BIN" % name48244825mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])4826self.mavproxy_load_module(mavproxy, 'log')4827self.wait_heartbeat()4828mavproxy.send("log list\n")4829mavproxy.expect("numLogs")4830# ensure the full list of logs has come out4831for i in range(5):4832self.wait_heartbeat()4833mavproxy.send("log download latest %s\n" % filename)4834mavproxy.expect("Finished downloading", timeout=120)4835self.mavproxy_unload_module(mavproxy, 'log')4836self.stop_mavproxy(mavproxy)48374838self.context_pop()48394840def TestLogDownloadMAVProxyCAN(self, upload_logs=False):4841"""Download latest log over CAN serial port"""4842self.context_push()4843self.set_parameters({4844"CAN_P1_DRIVER": 1,4845"LOG_DISARMED": 1,4846})4847self.reboot_sitl()4848self.set_parameters({4849"CAN_D1_UC_SER_EN": 1,4850"CAN_D1_UC_S1_NOD": 125,4851"CAN_D1_UC_S1_IDX": 4,4852"CAN_D1_UC_S1_BD": 57600,4853"CAN_D1_UC_S1_PRO": 2,4854})4855self.reboot_sitl()48564857self.set_parameter('SIM_SPEEDUP', 1)48584859filename = "MAVProxy-downloaded-can-log.BIN"4860# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:155504861mavproxy = self.start_mavproxy(master=':15550')4862mavproxy.expect("Detected vehicle")4863self.mavproxy_load_module(mavproxy, 'log')4864mavproxy.send("log list\n")4865mavproxy.expect("numLogs")4866# ensure the full list of logs has come out4867for i in range(5):4868self.wait_heartbeat()4869mavproxy.send("set shownoise 0\n")4870mavproxy.send("log download latest %s\n" % filename)4871mavproxy.expect("Finished downloading", timeout=120)4872self.mavproxy_unload_module(mavproxy, 'log')4873self.stop_mavproxy(mavproxy)4874self.context_pop()48754876def show_gps_and_sim_positions(self, on_off):4877"""Allow to display gps and actual position on map."""4878if on_off is True:4879# turn on simulator display of gps and actual position4880self.mavproxy.send('map set showgpspos 1\n')4881self.mavproxy.send('map set showsimpos 1\n')4882else:4883# turn off simulator display of gps and actual position4884self.mavproxy.send('map set showgpspos 0\n')4885self.mavproxy.send('map set showsimpos 0\n')48864887@staticmethod4888def mission_count(filename):4889"""Load a mission from a file and return number of waypoints."""4890wploader = mavwp.MAVWPLoader()4891wploader.load(filename)4892return wploader.count()48934894def install_message_hook(self, hook):4895self.message_hooks.append(hook)48964897def install_message_hook_context(self, hook):4898'''installs a message hook which will be removed when the context goes4899away'''4900if self.mav is None:4901return4902self.message_hooks.append(hook)4903self.context_get().message_hooks.append(hook)49044905def remove_message_hook(self, hook):4906'''remove hook from list of message hooks. Assumes it exists exactly4907once'''4908if self.mav is None:4909return4910self.message_hooks.remove(hook)4911if isinstance(hook, TestSuite.MessageHook):4912hook.hook_removed()49134914def install_example_script_context(self, scriptname):4915'''installs an example script which will be removed when the context goes4916away'''4917self.install_example_script(scriptname)4918self.context_get().installed_scripts.append(scriptname)49194920def install_test_script_context(self, scriptnames):4921'''installs an test script which will be removed when the context goes4922away'''4923if isinstance(scriptnames, str):4924scriptnames = [scriptnames]4925for scriptname in scriptnames:4926self.install_test_script(scriptname)4927self.context_get().installed_scripts.extend(scriptnames)49284929def install_test_scripts_context(self, *args, **kwargs):4930'''same as install_test_scripts_context - just pluralised name'''4931return self.install_test_script_context(*args, **kwargs)49324933def install_test_modules_context(self):4934'''installs test modules which will be removed when the context goes4935away'''4936self.install_test_modules()4937self.context_get().installed_modules.append("test")49384939def install_mavlink_module_context(self):4940'''installs mavlink module which will be removed when the context goes4941away'''4942self.install_mavlink_module()4943self.context_get().installed_modules.append("mavlink")49444945def install_applet_script_context(self, scriptname, **kwargs):4946'''installs an applet script which will be removed when the context goes4947away'''4948self.install_applet_script(scriptname, **kwargs)4949self.context_get().installed_scripts.append(scriptname)49504951def rootdir(self):4952this_dir = os.path.dirname(__file__)4953return os.path.realpath(os.path.join(this_dir, "../.."))49544955def ardupilot_stores_frame_for_cmd(self, t):4956# ardupilot doesn't remember frame on these commands4957return t not in [4958mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,4959mavutil.mavlink.MAV_CMD_CONDITION_YAW,4960mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,4961mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,4962mavutil.mavlink.MAV_CMD_DO_JUMP,4963mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,4964mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,4965mavutil.mavlink.MAV_CMD_DO_SET_SERVO,4966mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,4967]49684969def assert_mission_files_same(self, file1, file2, match_comments=False):4970self.progress("Comparing (%s) and (%s)" % (file1, file2, ))49714972f1 = open(file1)4973f2 = open(file2)4974lines1 = f1.readlines()4975lines2 = f2.readlines()49764977if not match_comments:4978# strip comments from all lines4979lines1 = [re.sub(r"\s*#.*", "", x, re.DOTALL) for x in lines1]4980lines2 = [re.sub(r"\s*#.*", "", x, re.DOTALL) for x in lines2]4981# FIXME: because DOTALL doesn't seem to work as expected:4982lines1 = [x.rstrip() for x in lines1]4983lines2 = [x.rstrip() for x in lines2]4984# remove now-empty lines:4985lines1 = filter(lambda x: len(x), lines1)4986lines2 = filter(lambda x: len(x), lines2)49874988for l1, l2 in zip(lines1, lines2):4989l1 = l1.rstrip("\r\n")4990l2 = l2.rstrip("\r\n")4991if l1 == l2:4992# e.g. the first "QGC WPL 110" line4993continue4994if re.match(r"0\s", l1):4995# home changes...4996continue4997l1 = l1.rstrip()4998l2 = l2.rstrip()4999fields1 = re.split(r"\s+", l1)5000fields2 = re.split(r"\s+", l2)5001# line = int(fields1[0])5002t = int(fields1[3]) # mission item type5003for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):5004if count == 2: # frame5005if not self.ardupilot_stores_frame_for_cmd(t):5006if int(i1) in [3, 10]: # 3 is relative, 10 is terrain5007i1 = 05008if int(i2) in [3, 10]:5009i2 = 05010if count == 6: # param 35011if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:5012# ardupilot canonicalises this to -1 for ccw or 1 for cw.5013if float(i1) == 0:5014i1 = 1.05015if float(i2) == 0:5016i2 = 1.05017if count == 7: # param 45018if t == mavutil.mavlink.MAV_CMD_NAV_LAND:5019# ardupilot canonicalises "0" to "1" param 4 (yaw)5020if int(float(i1)) == 0:5021i1 = 15022if int(float(i2)) == 0:5023i2 = 15024if 0 <= count <= 3 or 11 <= count <= 11:5025if int(i1) != int(i2):5026raise ValueError("Files have different content: (%s vs %s) (%s vs %s) (%d vs %d) (count=%u)" %5027(file1, file2, l1, l2, int(i1), int(i2), count)) # NOCI5028continue5029if 4 <= count <= 10:5030f_i1 = float(i1)5031f_i2 = float(i2)5032delta = abs(f_i1 - f_i2)5033max_allowed_delta = 0.0000095034if delta > max_allowed_delta:5035raise ValueError(5036("Files have different (float) content: " +5037"(%s) and (%s) " +5038"(%s vs %s) " +5039"(%f vs %f) " +5040"(%.10f) " +5041"(count=%u)") %5042(file1, file2,5043l1, l2,5044f_i1, f_i2,5045delta,5046count)) # NOCI5047continue5048raise ValueError("count %u not handled" % count)5049self.progress("Files same")50505051def assert_not_receive_message(self, message, timeout=1, mav=None, condition=None):5052'''this is like assert_not_receiving_message but uses sim time not5053wallclock time'''5054self.progress("making sure we're not getting %s messages" % message)5055if mav is None:5056mav = self.mav50575058tstart = self.get_sim_time_cached()5059while True:5060m = mav.recv_match(type=message, blocking=True, timeout=0.1, condition=condition)5061if m is not None:5062self.progress("Received: %s" % self.dump_message_verbose(m))5063raise PreconditionFailedException("Receiving %s messages" % message)5064if mav != self.mav:5065# update timestamp....5066self.drain_mav(self.mav)5067if self.get_sim_time_cached() - tstart > timeout:5068return50695070def assert_receive_message(self,5071type,5072timeout=None,5073verbose=False,5074very_verbose=False,5075mav=None,5076condition=None,5077delay_fn=None,5078instance=None,5079check_context=False):5080if timeout is None:5081timeout = 15082if mav is None:5083mav = self.mav50845085if check_context:5086collection = self.context_collection(type)5087if len(collection) > 0:5088# return the most-recently-received message:5089return collection[-1]50905091m = None5092tstart = time.time() # timeout in wallclock5093while True:5094m = mav.recv_match(type=type, blocking=True, timeout=0.05, condition=condition)5095if instance is not None:5096if getattr(m, m._instance_field) != instance:5097continue5098if m is not None:5099break5100elapsed_time = time.time() - tstart5101if elapsed_time > timeout:5102raise NotAchievedException("Did not get %s after %s seconds" %5103(type, elapsed_time))5104if delay_fn is not None:5105delay_fn()5106if verbose:5107self.progress("Received (%s)" % str(m))5108if very_verbose:5109self.progress(self.dump_message_verbose(m))5110return m51115112def assert_receive_named_value_float(self, name, timeout=10):5113tstart = self.get_sim_time_cached()5114while True:5115if self.get_sim_time_cached() - tstart > timeout:5116raise NotAchievedException("Did not get NAMED_VALUE_FLOAT %s" % name)5117m = self.assert_receive_message('NAMED_VALUE_FLOAT', verbose=1, very_verbose=1, timeout=timeout)5118if m.name != name:5119continue5120return m51215122def assert_receive_named_value_float_value(self, name, value, epsilon=0.0001, timeout=10):5123m = self.assert_receive_named_value_float_value(name, timeout=timeout)5124if abs(m.value - value) > epsilon:5125raise NotAchievedException("Bad %s want=%f got=%f" % (name, value, m.value))51265127def assert_rally_files_same(self, file1, file2):5128self.progress("Comparing (%s) and (%s)" % (file1, file2, ))5129f1 = open(file1)5130f2 = open(file2)5131lines_f1 = f1.readlines()5132lines_f2 = f2.readlines()5133self.assert_rally_content_same(lines_f1, lines_f2)51345135def assert_rally_filepath_content(self, file1, content):5136f1 = open(file1)5137lines_f1 = f1.readlines()5138lines_content = content.split("\n")5139print("lines content: %s" % str(lines_content))5140self.assert_rally_content_same(lines_f1, lines_content)51415142def assert_rally_content_same(self, f1, f2):5143'''check each line in f1 matches one-to-one with f2'''5144for l1, l2 in zip(f1, f2):5145print("l1: %s" % l1)5146print("l2: %s" % l2)5147l1 = l1.rstrip("\n")5148l2 = l2.rstrip("\n")5149l1 = l1.rstrip("\r")5150l2 = l2.rstrip("\r")5151if l1 == l2:5152# e.g. the first "QGC WPL 110" line5153continue5154if re.match(r"0\s", l1):5155# home changes...5156continue5157l1 = l1.rstrip()5158l2 = l2.rstrip()5159print("al1: %s" % str(l1))5160print("al2: %s" % str(l2))5161fields1 = re.split(r"\s+", l1)5162fields2 = re.split(r"\s+", l2)5163# line = int(fields1[0])5164# t = int(fields1[3]) # mission item type5165for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):5166# if count == 2: # frame5167# if t in [mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,5168# mavutil.mavlink.MAV_CMD_CONDITION_YAW,5169# mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,5170# mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,5171# mavutil.mavlink.MAV_CMD_DO_JUMP,5172# mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,5173# ]:5174# # ardupilot doesn't remember frame on these commands5175# if int(i1) == 3:5176# i1 = 05177# if int(i2) == 3:5178# i2 = 05179# if count == 6: # param 35180# if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:5181# # ardupilot canonicalises this to -1 for ccw or 1 for cw.5182# if float(i1) == 0:5183# i1 = 1.05184# if float(i2) == 0:5185# i2 = 1.05186# if count == 7: # param 45187# if t == mavutil.mavlink.MAV_CMD_NAV_LAND:5188# # ardupilot canonicalises "0" to "1" param 4 (yaw)5189# if int(float(i1)) == 0:5190# i1 = 15191# if int(float(i2)) == 0:5192# i2 = 15193if 0 <= count <= 3 or 11 <= count <= 11:5194if int(i1) != int(i2):5195raise ValueError("Rally points different: (%s vs %s) (%d vs %d) (count=%u)" %5196(l1, l2, int(i1), int(i2), count)) # NOCI5197continue5198if 4 <= count <= 10:5199f_i1 = float(i1)5200f_i2 = float(i2)5201delta = abs(f_i1 - f_i2)5202max_allowed_delta = 0.0000095203if delta > max_allowed_delta:5204raise ValueError(5205("Rally has different (float) content: " +5206"(%s vs %s) " +5207"(%f vs %f) " +5208"(%.10f) " +5209"(count=%u)") %5210(l1, l2,5211f_i1, f_i2,5212delta,5213count)) # NOCI5214continue5215raise ValueError("count %u not handled" % count)5216self.progress("Rally content same")52175218def load_rally_using_mavproxy(self, filename):5219"""Load rally points from a file to flight controller."""5220self.progress("Loading rally points (%s)" % filename)5221path = os.path.join(testdir, self.current_test_name_directory, filename)5222mavproxy = self.start_mavproxy()5223mavproxy.send('rally load %s\n' % path)5224mavproxy.expect("Loaded")5225self.delay_sim_time(10) # allow transfer to complete5226self.stop_mavproxy(mavproxy)52275228def load_sample_mission(self):5229self.load_mission(self.sample_mission_filename())52305231def generic_mission_filepath_for_filename(self, filename):5232return os.path.join(testdir, "Generic_Missions", filename)52335234def load_generic_mission(self, filename, strict=True):5235return self.load_mission_from_filepath(5236self.generic_mission_filepath_for_filename(filename),5237strict=strict)52385239def load_mission(self, filename, strict=True):5240return self.load_mission_from_filepath(5241os.path.join(testdir, self.current_test_name_directory, filename),5242strict=strict)52435244def wp_to_mission_item_int(self, wp, mission_type):5245'''convert a MISSION_ITEM to a MISSION_ITEM_INT. We always send as5246MISSION_ITEM_INT to give cm level accuracy5247Swiped from mavproxy_wp.py5248'''5249if wp.get_type() == 'MISSION_ITEM_INT':5250return wp5251wp_int = mavutil.mavlink.MAVLink_mission_item_int_message(5252wp.target_system,5253wp.target_component,5254wp.seq,5255wp.frame,5256wp.command,5257wp.current,5258wp.autocontinue,5259wp.param1,5260wp.param2,5261wp.param3,5262wp.param4,5263int(wp.x*1.0e7),5264int(wp.y*1.0e7),5265wp.z,5266mission_type,5267)5268return wp_int52695270def mission_item_protocol_items_from_filepath(self,5271loaderclass,5272filepath,5273target_system=1,5274target_component=1,5275):5276'''returns a list of mission-item-ints from filepath'''5277# self.progress("filepath: %s" % filepath)5278wploader = loaderclass(5279target_system=target_system,5280target_component=target_component5281)5282itemstype = mavutil.mavlink.enums["MAV_MISSION_TYPE"][wploader.mav_mission_type()]5283self.progress(f"Loading {itemstype} ({os.path.basename(filepath)}")5284wploader.load(filepath)5285return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:50252865287def mission_from_filepath(self, filepath, target_system=1, target_component=1):5288'''returns a list of mission-item-ints from filepath'''5289return self.mission_item_protocol_items_from_filepath(5290mavwp.MAVWPLoader,5291filepath,5292target_system=target_system,5293target_component=target_component,5294)52955296def sitl_home_string_from_mission(self, filename):5297'''return a string of the form "lat,lng,yaw,alt" from the home5298location in a mission file'''5299return "%s,%s,%s,%s" % self.get_home_tuple_from_mission(filename)53005301def sitl_home_string_from_mission_filepath(self, filepath):5302'''return a string of the form "lat,lng,yaw,alt" from the home5303location in a mission file'''5304return "%s,%s,%s,%s" % self.get_home_tuple_from_mission_filepath(filepath)53055306def get_home_tuple_from_mission(self, filename):5307'''gets item 0 from the mission file, returns a tuple suitable for5308passing to customise_SITL_commandline as --home. Yaw will be53090, so the caller may want to fill that in5310'''5311return self.get_home_tuple_from_mission_filepath(5312os.path.join(testdir, self.current_test_name_directory, filename)5313)53145315def get_home_location_from_mission(self, filename):5316(home_lat, home_lon, home_alt, heading) = self.get_home_tuple_from_mission("rover-path-planning-mission.txt")5317return mavutil.location(home_lat, home_lon)53185319def get_home_tuple_from_mission_filepath(self, filepath):5320'''gets item 0 from the mission file, returns a tuple suitable for5321passing to customise_SITL_commandline as --home. Yaw will be53220, so the caller may want to fill that in5323'''5324items = self.mission_from_filepath(filepath)5325home_item = items[0]5326return (home_item.x * 1e-7, home_item.y * 1e-7, home_item.z, 0)53275328# TODO: rename the following to "upload_mission_from_filepath"5329def load_mission_from_filepath(self,5330filepath,5331target_system=1,5332target_component=1,5333strict=True,5334reset_current_wp=True):5335wpoints_int = self.mission_from_filepath(5336filepath,5337target_system=target_system,5338target_component=target_component5339)5340self.check_mission_upload_download(wpoints_int, strict=strict)5341if reset_current_wp:5342# ArduPilot doesn't reset the current waypoint by default5343# we may be in auto mode and running waypoints, so we5344# can't check the current waypoint after resetting it.5345self.set_current_waypoint(0, check_afterwards=False)5346return len(wpoints_int)53475348def load_mission_using_mavproxy(self, mavproxy, filename):5349return self.load_mission_from_filepath_using_mavproxy(5350mavproxy,5351self.current_test_name_directory,5352filename)53535354def load_mission_from_filepath_using_mavproxy(self,5355mavproxy,5356filepath,5357filename):5358"""Load a mission from a file to flight controller."""5359self.progress("Loading mission (%s)" % filename)5360path = os.path.join(testdir, filepath, filename)5361tstart = self.get_sim_time()5362while True:5363t2 = self.get_sim_time()5364if t2 - tstart > 10:5365raise AutoTestTimeoutException("Failed to do waypoint thing")5366# the following hack is to get around MAVProxy statustext deduping:5367while time.time() - self.last_wp_load < 3:5368self.progress("Waiting for MAVProxy de-dupe timer to expire")5369self.drain_mav()5370time.sleep(0.1)5371mavproxy.send('wp load %s\n' % path)5372mavproxy.expect('Loaded ([0-9]+) waypoints from')5373load_count = mavproxy.match.group(1)5374self.last_wp_load = time.time()5375mavproxy.expect("Flight plan received")5376mavproxy.send('wp list\n')5377mavproxy.expect('Requesting ([0-9]+) waypoints')5378request_count = mavproxy.match.group(1)5379if load_count != request_count:5380self.progress("request_count=%s != load_count=%s" %5381(request_count, load_count))5382continue5383mavproxy.expect('Saved ([0-9]+) waypoints to (.+?way.txt)')5384save_count = mavproxy.match.group(1)5385if save_count != request_count:5386raise NotAchievedException("request count != load count")5387# warning: this assumes MAVProxy was started in the CWD!5388# on the autotest server we invoke autotest.py one-up from5389# the git root, like this:5390# timelimit 32000 APM/Tools/autotest/autotest.py --timeout=30000 > buildlogs/autotest-output.txt 2>&15391# that means the MAVProxy log files are not reltopdir!5392saved_filepath = mavproxy.match.group(2)5393saved_filepath = saved_filepath.rstrip()5394self.assert_mission_files_same(path, saved_filepath)5395break5396mavproxy.send('wp status\n')5397mavproxy.expect(r'Have (\d+) of (\d+)')5398status_have = mavproxy.match.group(1)5399status_want = mavproxy.match.group(2)5400if status_have != status_want:5401raise ValueError("status count mismatch")5402if status_have != save_count:5403raise ValueError("status have not equal to save count")54045405wploader = mavwp.MAVWPLoader()5406wploader.load(path)5407num_wp = wploader.count()5408if num_wp != int(status_have):5409raise ValueError("num_wp=%u != status_have=%u" %5410(num_wp, int(status_have)))5411if num_wp == 0:5412raise ValueError("No waypoints loaded?!")54135414return num_wp54155416def save_mission_to_file_using_mavproxy(self, mavproxy, filename):5417"""Save a mission to a file"""5418mavproxy.send('wp list\n')5419mavproxy.expect('Requesting [0-9]+ waypoints')5420mavproxy.send('wp save %s\n' % filename)5421mavproxy.expect('Saved ([0-9]+) waypoints')5422num_wp = int(mavproxy.match.group(1))5423self.progress("num_wp: %d" % num_wp)5424return num_wp54255426def string_for_frame(self, frame):5427return mavutil.mavlink.enums["MAV_FRAME"][frame].name54285429def frames_equivalent(self, f1, f2):5430pairs = [5431(mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,5432mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT),5433(mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,5434mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT),5435(mavutil.mavlink.MAV_FRAME_GLOBAL,5436mavutil.mavlink.MAV_FRAME_GLOBAL_INT),5437]5438for pair in pairs:5439if (f1 == pair[0] and f2 == pair[1]):5440return True5441if (f1 == pair[1] and f2 == pair[0]):5442return True5443return f1 == f254445445def check_mission_items_same(self,5446check_atts,5447want,5448got,5449epsilon=None,5450skip_first_item=False,5451strict=True):5452self.progress("Checking mission items same")5453if epsilon is None:5454epsilon = 15455if len(want) != len(got):5456raise NotAchievedException("Incorrect item count (want=%u got=%u)" % (len(want), len(got)))5457self.progress("Checking %u items" % len(want))5458for i in range(0, len(want)):5459if skip_first_item and i == 0:5460continue5461item = want[i]5462downloaded_item = got[i]54635464check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']5465# z is not preserved54665467self.progress("Comparing (%s) and (%s)" % (str(item), str(downloaded_item)))54685469for att in check_atts:5470item_val = getattr(item, att)5471downloaded_item_val = getattr(downloaded_item, att)5472if abs(item_val - downloaded_item_val) > epsilon:5473raise NotAchievedException(5474"Item %u (%s) has different %s after download want=%s got=%s (got-item=%s)" %5475(i, str(item), att, str(item_val), str(downloaded_item_val), str(downloaded_item)))5476# for waypoint items ensure z and frame are preserved:5477self.progress("Type is %u" % got[0].mission_type)5478if got[0].mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:5479item_val = getattr(item, 'frame')5480downloaded_item_val = getattr(downloaded_item, 'frame')5481# if you are thinking of adding another, "don't annoy5482# me, I know missions aren't troundtripped" non-strict5483# thing here, DON'T do it without first checking "def5484# assert_mission_files_same"; it makes the same checks5485# as will be needed here eventually.5486if ((strict or self.ardupilot_stores_frame_for_cmd(getattr(item, 'command'))) and5487not self.frames_equivalent(item_val, downloaded_item_val)):5488raise NotAchievedException("Frame not same (got=%s want=%s)" %5489(self.string_for_frame(downloaded_item_val),5490self.string_for_frame(item_val)))5491if downloaded_item.z == 0:5492delta = abs(item.z)5493else:5494delta = 1 - abs(item.z / downloaded_item.z)5495if delta > 0.01: # error should be less than 1 mm, but float precision issues in Python...5496raise NotAchievedException("Z not preserved (got=%f want=%f delta=%f%%)" %5497(downloaded_item.z, item.z, delta))54985499def check_fence_items_same(self, want, got, strict=True):5500check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']5501return self.check_mission_items_same(check_atts, want, got, strict=strict)55025503def check_mission_waypoint_items_same(self, want, got, strict=True):5504check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']5505return self.check_mission_items_same(check_atts, want, got, skip_first_item=True, strict=strict)55065507def check_mission_item_upload_download(self, items, itype, mission_type, strict=True):5508self.progress("check %s upload/download: upload %u items" %5509(itype, len(items),))5510self.upload_using_mission_protocol(mission_type, items)5511self.progress("check %s upload/download: download items" % itype)5512downloaded_items = self.download_using_mission_protocol(mission_type)5513if len(items) != len(downloaded_items):5514raise NotAchievedException("Did not download same number of items as uploaded want=%u got=%u" %5515(len(items), len(downloaded_items)))5516if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_FENCE:5517self.check_fence_items_same(items, downloaded_items, strict=strict)5518elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:5519self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)5520elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY:5521self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)5522else:5523raise NotAchievedException("Unhandled")55245525def check_fence_upload_download(self, items):5526self.check_mission_item_upload_download(5527items,5528"fence",5529mavutil.mavlink.MAV_MISSION_TYPE_FENCE)5530if self.use_map and self.mavproxy is not None:5531self.mavproxy.send('fence list\n')55325533def check_mission_upload_download(self, items, strict=True):5534self.check_mission_item_upload_download(5535items,5536"waypoints",5537mavutil.mavlink.MAV_MISSION_TYPE_MISSION,5538strict=strict)5539if self.use_map and self.mavproxy is not None:5540self.mavproxy.send('wp list\n')55415542def check_rally_upload_download(self, items):5543self.check_mission_item_upload_download(5544items,5545"rally",5546mavutil.mavlink.MAV_MISSION_TYPE_RALLY5547)5548if self.use_map and self.mavproxy is not None:5549self.mavproxy.send('rally list\n')55505551def check_dflog_message_rates(self, log_filepath, message_rates):5552reader = self.dfreader_for_path(log_filepath)55535554counts = {}5555first = None5556while True:5557m = reader.recv_match()5558if m is None:5559break5560if (m.fmt.instance_field is not None and5561getattr(m, m.fmt.instance_field) != 0):5562continue55635564t = m.get_type()5565# print("t=%s" % str(t))5566if t not in counts:5567counts[t] = 05568counts[t] += 155695570if hasattr(m, 'TimeUS'):5571if first is None:5572first = m5573last = m55745575if first is None:5576raise NotAchievedException("Did not get any messages")5577delta_time_us = last.TimeUS - first.TimeUS55785579for (t, want_rate) in message_rates.items():5580if t not in counts:5581raise NotAchievedException("Wanted %s but got none" % t)5582self.progress("Got (%u) in (%uus)" % (counts[t], delta_time_us))5583got_rate = float(counts[t]) / delta_time_us * 100000055845585if abs(want_rate - got_rate) > 5:5586raise NotAchievedException("Not getting %s data at wanted rate want=%f got=%f" %5587(t, want_rate, got_rate))55885589def generate_rate_sample_log(self):5590self.reboot_sitl()5591self.wait_ready_to_arm()5592self.delay_sim_time(20)5593path = self.current_onboard_log_filepath()5594self.progress("Rate sample log (%s)" % path)5595self.reboot_sitl()5596return path55975598def rc_defaults(self):5599return {56001: 1500,56012: 1500,56023: 1500,56034: 1500,56045: 1500,56056: 1500,56067: 1500,56078: 1500,56089: 1500,560910: 1500,561011: 1500,561112: 1500,561213: 1500,561314: 1500,561415: 1500,561516: 1500,5616}56175618def set_rc_from_map(self, _map, timeout=20):5619map_copy = _map.copy()5620for v in map_copy.values():5621if not isinstance(v, int):5622raise NotAchievedException("RC values must be integers")5623self.rc_queue.put(map_copy)56245625if self.rc_thread is None:5626self.rc_thread = threading.Thread(target=self.rc_thread_main, name='RC')5627if self.rc_thread is None:5628raise NotAchievedException("Could not create thread")5629self.rc_thread.start()56305631tstart = self.get_sim_time()5632while True:5633if tstart - self.get_sim_time_cached() > timeout:5634raise NotAchievedException("Failed to set RC values")5635m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=1)5636if m is None:5637continue5638bad_channels = ""5639for chan in map_copy:5640chan_pwm = getattr(m, "chan" + str(chan) + "_raw")5641if chan_pwm != map_copy[chan]:5642bad_channels += " (ch=%u want=%u got=%u)" % (chan, map_copy[chan], chan_pwm)5643break5644if len(bad_channels) == 0:5645self.progress("RC values good")5646break5647self.progress("RC values bad:%s" % bad_channels)5648if not self.rc_thread.is_alive():5649self.rc_thread = None5650raise ValueError("RC thread is dead") # FIXME: type56515652def rc_thread_main(self):5653chan16 = [1000] * 1656545655sitl_output = mavutil.mavudp("127.0.0.1:%u" % self.sitl_rcin_port(), input=False)5656buf = None56575658while True:5659if self.rc_thread_should_quit:5660break56615662# the 0.05 here means we're updating the RC values into5663# the autopilot at 20Hz - that's our 50Hz wallclock, , not5664# the autopilot's simulated 20Hz, so if speedup is 10 the5665# autopilot will see ~2Hz.5666timeout = 0.025667# ... and 2Hz is too slow when we now run at 100x speedup:5668timeout /= (self.speedup / 10.0)56695670try:5671map_copy = self.rc_queue.get(timeout=timeout)56725673# 16 packed entries:5674for i in range(1, 17):5675if i in map_copy:5676chan16[i-1] = map_copy[i]56775678except Queue.Empty:5679pass56805681buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)56825683if buf is None:5684continue56855686sitl_output.write(buf)56875688def set_rc_default(self):5689"""Setup all simulated RC control to 1500."""5690_defaults = self.rc_defaults()5691self.set_rc_from_map(_defaults)56925693def check_rc_defaults(self):5694"""Ensure all rc outputs are at defaults"""5695self.do_timesync_roundtrip()5696_defaults = self.rc_defaults()5697m = self.assert_receive_message('RC_CHANNELS', timeout=5)5698need_set = {}5699for chan in _defaults:5700default_value = _defaults[chan]5701current_value = getattr(m, "chan" + str(chan) + "_raw")5702if default_value != current_value:5703self.progress("chan=%u needs resetting is=%u want=%u" %5704(chan, current_value, default_value))5705need_set[chan] = default_value5706self.set_rc_from_map(need_set)57075708def set_rc(self, chan, pwm, timeout=20):5709"""Setup a simulated RC control to a PWM value"""5710self.set_rc_from_map({chan: pwm}, timeout=timeout)57115712def set_servo(self, chan, pwm):5713"""Replicate the functionality of MAVProxy: servo set <ch> <pwm>"""5714self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm)57155716def location_offset_ne(self, location, north, east):5717'''move location in metres'''5718print("old: %f %f" % (location.lat, location.lng))5719(lat, lng) = mp_util.gps_offset(location.lat, location.lng, east, north)5720location.lat = lat5721location.lng = lng5722print("new: %f %f" % (location.lat, location.lng))57235724def home_relative_loc_ne(self, n, e):5725ret = self.home_position_as_mav_location()5726self.location_offset_ne(ret, n, e)5727return ret57285729def home_relative_loc_neu(self, n, e, u):5730ret = self.home_position_as_mav_location()5731self.location_offset_ne(ret, n, e)5732ret.alt += u5733return ret57345735def zero_throttle(self):5736"""Set throttle to zero."""5737if self.is_rover():5738self.set_rc(3, 1500)5739else:5740self.set_rc(3, 1000)57415742def set_output_to_max(self, chan):5743"""Set output to max with RC Radio taking into account REVERSED parameter."""5744is_reversed = self.get_parameter("RC%u_REVERSED" % chan)5745out_max = int(self.get_parameter("RC%u_MAX" % chan))5746out_min = int(self.get_parameter("RC%u_MIN" % chan))5747if is_reversed == 0:5748self.set_rc(chan, out_max)5749else:5750self.set_rc(chan, out_min)57515752def set_output_to_min(self, chan):5753"""Set output to min with RC Radio taking into account REVERSED parameter."""5754is_reversed = self.get_parameter("RC%u_REVERSED" % chan)5755out_max = int(self.get_parameter("RC%u_MAX" % chan))5756out_min = int(self.get_parameter("RC%u_MIN" % chan))5757if is_reversed == 0:5758self.set_rc(chan, out_min)5759else:5760self.set_rc(chan, out_max)57615762def set_output_to_trim(self, chan):5763"""Set output to trim with RC Radio."""5764out_trim = int(self.get_parameter("RC%u_TRIM" % chan))5765self.set_rc(chan, out_trim)57665767def get_stick_arming_channel(self):5768"""Return the Rudder channel number as set in parameter."""5769raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))57705771def get_disarm_delay(self):5772"""Return disarm delay value."""5773raise ErrorException("Disarm delay is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))57745775def arming_test_mission(self):5776"""Load arming test mission.5777This mission is used to allow to change mode to AUTO. For each vehicle5778it get an unlimited wait waypoint and the starting takeoff if needed."""5779if self.is_rover() or self.is_plane() or self.is_sub():5780return os.path.join(testdir, self.current_test_name_directory + "test_arming.txt")5781else:5782return None57835784def set_safetyswitch_on(self, **kwargs):5785self.set_safetyswitch(1, **kwargs)57865787def set_safetyswitch_off(self, **kwargs):5788self.set_safetyswitch(0, **kwargs)57895790def set_safetyswitch(self, value, target_system=1, target_component=1):5791self.mav.mav.set_mode_send(5792target_system,5793mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,5794value)5795self.wait_sensor_state(5796mavutil.mavlink.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,5797True, not value, True,5798verbose=True,5799timeout=305800)58015802def armed(self):5803"""Return True if vehicle is armed and safetyoff"""5804m = self.wait_heartbeat()5805return (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 058065807def send_mavlink_arm_command(self):5808self.send_cmd(5809mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5810p1=1, # ARM5811)58125813def send_mavlink_disarm_command(self):5814self.send_cmd(5815mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5816p1=0, # DISARM5817)58185819def send_mavlink_run_prearms_command(self):5820self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)58215822def analog_rangefinder_parameters(self):5823return {5824"RNGFND1_TYPE": 1,5825"RNGFND1_MIN_CM": 0,5826"RNGFND1_MAX_CM": 4000,5827"RNGFND1_SCALING": 12.12,5828"RNGFND1_PIN": 0,5829}58305831def set_analog_rangefinder_parameters(self):5832self.set_parameters(self.analog_rangefinder_parameters())58335834def send_debug_trap(self, timeout=6000):5835self.progress("Sending trap to autopilot")5836self.run_cmd(5837mavutil.mavlink.MAV_CMD_DEBUG_TRAP,5838p1=32451, # magic number to trap5839timeout=timeout,5840)58415842def try_arm(self, result=True, expect_msg=None, timeout=60):5843"""Send Arming command, wait for the expected result and statustext."""5844self.progress("Try arming and wait for expected result")5845self.drain_mav()5846self.run_cmd(5847mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5848p1=1, # ARM5849want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,5850timeout=timeout,5851)5852if expect_msg is not None:5853self.wait_statustext(5854expect_msg,5855timeout=timeout,5856the_function=lambda: self.send_cmd(5857mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5858p1=1, # ARM5859target_sysid=None,5860target_compid=None,5861))58625863def arm_vehicle(self, timeout=20, force=False):5864"""Arm vehicle with mavlink arm message."""5865self.progress("Arm motors with MAVLink cmd")5866p2 = 05867if force:5868p2 = 29895869try:5870self.run_cmd(5871mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5872p1=1, # ARM5873p2=p2,5874timeout=timeout,5875)5876except ValueError as e:5877# statustexts are queued; give it a second to arrive:5878self.delay_sim_time(5)5879raise e5880try:5881self.wait_armed()5882except AutoTestTimeoutException:5883raise AutoTestTimeoutException("Failed to ARM with mavlink")5884return True58855886def wait_armed(self, timeout=20):5887tstart = self.get_sim_time()5888while self.get_sim_time_cached() - tstart < timeout:5889self.wait_heartbeat(drain_mav=False)5890if self.mav.motors_armed():5891self.progress("Motors ARMED")5892return5893raise AutoTestTimeoutException("Did not become armed")58945895def disarm_vehicle(self, timeout=60, force=False):5896"""Disarm vehicle with mavlink disarm message."""5897self.progress("Disarm motors with MAVLink cmd")5898p2 = 05899if force:5900p2 = 21196 # magic force disarm value5901self.run_cmd(5902mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5903p1=0, # DISARM5904p2=p2,5905timeout=timeout,5906)5907self.wait_disarmed()59085909def disarm_vehicle_expect_fail(self):5910'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''5911self.progress("Disarm - expect to fail")5912self.run_cmd(5913mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5914p1=0, # DISARM5915timeout=10,5916want_result=mavutil.mavlink.MAV_RESULT_FAILED,5917)5918self.progress("Disarm - forced")5919self.disarm_vehicle(force=True)59205921def wait_disarmed_default_wait_time(self):5922return 3059235924def wait_disarmed(self, timeout=None, tstart=None):5925if timeout is None:5926timeout = self.wait_disarmed_default_wait_time()5927self.progress("Waiting for DISARM")5928if tstart is None:5929tstart = self.get_sim_time()5930last_print_time = 05931while True:5932now = self.get_sim_time_cached()5933delta = now - tstart5934if delta > timeout:5935raise AutoTestTimeoutException("Failed to DISARM within %fs" %5936(timeout,))5937if now - last_print_time > 1:5938self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout))5939last_print_time = now5940msg = self.wait_heartbeat(quiet=True)5941if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:5942# still armed5943continue5944self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %5945(delta, timeout))5946return59475948def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'):5949'''wait for an attitude (degrees)'''5950if desroll is None and despitch is None:5951raise ValueError("despitch or desroll must be supplied")5952tstart = self.get_sim_time()5953while True:5954if self.get_sim_time_cached() - tstart > timeout:5955raise AutoTestTimeoutException("Failed to achieve attitude")5956m = self.assert_receive_message(message_type, timeout=60)5957roll_deg = math.degrees(m.roll)5958pitch_deg = math.degrees(m.pitch)5959self.progress("wait_att: roll=%f desroll=%s pitch=%f despitch=%s" %5960(roll_deg, desroll, pitch_deg, despitch))5961if desroll is not None and abs(roll_deg - desroll) > tolerance:5962continue5963if despitch is not None and abs(pitch_deg - despitch) > tolerance:5964continue5965return59665967def wait_attitude_quaternion(self,5968desroll=None,5969despitch=None,5970timeout=2,5971tolerance=10,5972message_type='ATTITUDE_QUATERNION'):5973'''wait for an attitude (degrees)'''5974if desroll is None and despitch is None:5975raise ValueError("despitch or desroll must be supplied")5976tstart = self.get_sim_time()5977while True:5978if self.get_sim_time_cached() - tstart > timeout:5979raise AutoTestTimeoutException("Failed to achieve attitude")5980m = self.poll_message(message_type)5981q = quaternion.Quaternion([m.q1, m.q2, m.q3, m.q4])5982euler = q.euler5983roll = euler[0]5984pitch = euler[1]5985roll_deg = math.degrees(roll)5986pitch_deg = math.degrees(pitch)5987self.progress("wait_att_quat: roll=%f desroll=%s pitch=%f despitch=%s" %5988(roll_deg, desroll, pitch_deg, despitch))5989if desroll is not None and abs(roll_deg - desroll) > tolerance:5990continue5991if despitch is not None and abs(pitch_deg - despitch) > tolerance:5992continue5993self.progress("wait_att_quat: achieved")5994return59955996def CPUFailsafe(self):5997'''Ensure we do something appropriate when the main loop stops'''5998# Most vehicles just disarm on failsafe5999# customising the SITL commandline ensures the process will6000# get stopped/started at the end of the test6001if self.frame is None:6002raise ValueError("Frame is none?")6003self.customise_SITL_commandline([])6004self.wait_ready_to_arm()6005self.arm_vehicle()6006self.progress("Sending enter-cpu-lockup")6007# when we're in CPU lockup we don't get SYSTEM_TIME messages,6008# so get_sim_time breaks:6009tstart = self.get_sim_time()6010self.send_cmd_enter_cpu_lockup()6011self.wait_disarmed(timeout=5, tstart=tstart)6012# we're not getting SYSTEM_TIME messages at this point.... and6013# we're in a weird state where the vehicle is armed but the6014# motors are not, and we can't disarm further because Copter6015# looks at whether its *motors* are armed as part of its6016# disarm process.6017self.reset_SITL_commandline()60186019def cpufailsafe_wait_servo_channel_value(self, channel, value, timeout=30):6020'''we get restricted messages while doing cpufailsafe, this working then'''6021start = time.time()6022while True:6023if time.time() - start > timeout:6024raise NotAchievedException("Did not achieve value")6025m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)6026channel_field = "servo%u_raw" % channel6027m_value = getattr(m, channel_field, None)6028self.progress("Servo%u=%u want=%u" % (channel, m_value, value))6029if m_value == value:6030break60316032def plane_CPUFailsafe(self):6033'''In lockup Plane should copy RC inputs to RC outputs'''6034# customising the SITL commandline ensures the process will6035# get stopped/started at the end of the test6036self.customise_SITL_commandline([])6037self.wait_ready_to_arm()6038self.arm_vehicle()6039self.progress("Sending enter-cpu-lockup")6040# when we're in CPU lockup we don't get SYSTEM_TIME messages,6041# so get_sim_time breaks:6042self.send_cmd_enter_cpu_lockup()6043start_time = time.time() # not sim time!6044self.context_push()6045self.context_collect("STATUSTEXT")6046while True:6047want = "Initialising ArduPilot"6048if time.time() - start_time > 30:6049raise NotAchievedException("Did not get %s" % want)6050# we still need to parse the incoming messages:6051try:6052self.wait_statustext(want, timeout=0.1, check_context=True, wallclock_timeout=1)6053break6054except AutoTestTimeoutException:6055pass6056self.context_pop()6057# Different scaling for RC input and servo output means the6058# servo output value isn't the rc input value:6059self.progress("Setting RC to 1200")6060self.rc_queue.put({2: 1200})6061self.progress("Waiting for servo of 1260")6062self.cpufailsafe_wait_servo_channel_value(2, 1260)6063self.rc_queue.put({2: 1700})6064self.cpufailsafe_wait_servo_channel_value(2, 1660)6065self.reset_SITL_commandline()60666067def mavproxy_arm_vehicle(self, mavproxy):6068"""Arm vehicle with mavlink arm message send from MAVProxy."""6069self.progress("Arm motors with MavProxy")6070mavproxy.send('arm throttle\n')6071self.wait_armed()6072self.progress("ARMED")6073return True60746075def mavproxy_disarm_vehicle(self, mavproxy):6076"""Disarm vehicle with mavlink disarm message send from MAVProxy."""6077self.progress("Disarm motors with MavProxy")6078mavproxy.send('disarm\n')6079self.wait_disarmed()60806081def arm_motors_with_rc_input(self, timeout=20):6082"""Arm motors with radio."""6083self.progress("Arm motors with radio")6084self.set_output_to_max(self.get_stick_arming_channel())6085tstart = self.get_sim_time()6086while True:6087self.wait_heartbeat()6088tdelta = self.get_sim_time_cached() - tstart6089if self.mav.motors_armed():6090self.progress("MOTORS ARMED OK WITH RADIO")6091self.set_output_to_trim(self.get_stick_arming_channel())6092self.progress("Arm in %ss" % tdelta) # TODO check arming time6093return6094self.progress("Not armed after %f seconds" % (tdelta))6095if tdelta > timeout:6096break6097self.set_output_to_trim(self.get_stick_arming_channel())6098raise NotAchievedException("Failed to ARM with radio")60996100def disarm_motors_with_rc_input(self, timeout=20, watch_for_disabled=False):6101"""Disarm motors with radio."""6102self.progress("Disarm motors with radio")6103self.do_timesync_roundtrip()6104self.context_push()6105self.context_collect('STATUSTEXT')6106self.set_output_to_min(self.get_stick_arming_channel())6107tstart = self.get_sim_time()6108ret = False6109while self.get_sim_time_cached() < tstart + timeout:6110self.wait_heartbeat()6111if not self.mav.motors_armed():6112disarm_delay = self.get_sim_time_cached() - tstart6113self.progress("MOTORS DISARMED OK WITH RADIO (in %ss)" % disarm_delay)6114ret = True6115break6116if self.statustext_in_collections("Rudder disarm: disabled"):6117self.progress("Found 'Rudder disarm: disabled' in statustext")6118break6119self.context_clear_collection('STATUSTEXT')6120self.set_output_to_trim(self.get_stick_arming_channel())6121self.context_pop()6122if not ret:6123raise NotAchievedException("Failed to DISARM with RC input")61246125def arm_motors_with_switch(self, switch_chan, timeout=20):6126"""Arm motors with switch."""6127self.progress("Arm motors with switch %d" % switch_chan)6128self.set_rc(switch_chan, 2000)6129tstart = self.get_sim_time()6130while self.get_sim_time_cached() - tstart < timeout:6131self.wait_heartbeat()6132if self.mav.motors_armed():6133self.progress("MOTORS ARMED OK WITH SWITCH")6134return6135raise NotAchievedException("Failed to ARM with switch")61366137def disarm_motors_with_switch(self, switch_chan, timeout=20):6138"""Disarm motors with switch."""6139self.progress("Disarm motors with switch %d" % switch_chan)6140self.set_rc(switch_chan, 1000)6141tstart = self.get_sim_time()6142while self.get_sim_time_cached() < tstart + timeout:6143self.wait_heartbeat()6144if not self.mav.motors_armed():6145self.progress("MOTORS DISARMED OK WITH SWITCH")6146return6147raise NotAchievedException("Failed to DISARM with switch")61486149def disarm_wait(self, timeout=10):6150tstart = self.get_sim_time()6151while True:6152if self.get_sim_time_cached() - tstart > timeout:6153raise NotAchievedException("Did not disarm")6154self.wait_heartbeat()6155if not self.mav.motors_armed():6156return61576158def wait_autodisarm_motors(self):6159"""Wait for Autodisarm motors within disarm delay6160this feature is only available in copter (DISARM_DELAY) and plane (LAND_DISARMDELAY)."""6161self.progress("Wait autodisarming motors")6162disarm_delay = self.get_disarm_delay()6163tstart = self.get_sim_time()6164timeout = disarm_delay * 26165while self.get_sim_time_cached() < tstart + timeout:6166self.wait_heartbeat()6167if not self.mav.motors_armed():6168disarm_time = self.get_sim_time_cached() - tstart6169self.progress("MOTORS AUTODISARMED")6170self.progress("Autodisarm in %ss, expect less than %ss" % (disarm_time, disarm_delay))6171return disarm_time <= disarm_delay6172raise AutoTestTimeoutException("Failed to AUTODISARM")61736174def set_autodisarm_delay(self, delay):6175"""Set autodisarm delay"""6176raise ErrorException("Auto disarm is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))61776178@staticmethod6179def should_fetch_all_for_parameter_change(param_name):6180return False # FIXME: if we allow MAVProxy then allow this6181if fnmatch.fnmatch(param_name, "*_ENABLE") or fnmatch.fnmatch(param_name, "*_ENABLED"):6182return True6183if param_name in ["ARSPD_TYPE",6184"ARSPD2_TYPE",6185"BATT2_MONITOR",6186"CAN_DRIVER",6187"COMPASS_PMOT_EN",6188"OSD_TYPE",6189"RSSI_TYPE",6190"WENC_TYPE"]:6191return True6192return False61936194def send_set_parameter_direct(self, name, value):6195self.mav.mav.param_set_send(self.sysid_thismav(),61961,6197name.encode('ascii'),6198value,6199mavutil.mavlink.MAV_PARAM_TYPE_REAL32)62006201def send_set_parameter_mavproxy(self, name, value):6202self.mavproxy.send("param set %s %s\n" % (name, str(value)))62036204def send_set_parameter(self, name, value, verbose=False):6205if verbose:6206self.progress("Send set param for (%s) (%f)" % (name, value))6207return self.send_set_parameter_direct(name, value)62086209def set_parameter(self, name, value, **kwargs):6210self.set_parameters({name: value}, **kwargs)62116212def set_parameters(self, parameters, add_to_context=True, epsilon_pct=0.00001, verbose=True, attempts=None):6213"""Set parameters from vehicle."""62146215want = copy.copy(parameters)6216self.progress("set_parameters: (%s)" % str(want))6217self.drain_mav()6218if len(want) == 0:6219return62206221if attempts is None:6222# we can easily fill ArduPilot's param-set/param-get queue6223# which is quite short. So we retry *a lot*.6224attempts = len(want) * 1062256226param_value_messages = []62276228def add_param_value(mav, m):6229t = m.get_type()6230if t != "PARAM_VALUE":6231return6232param_value_messages.append(m)62336234self.install_message_hook(add_param_value)62356236original_values = {}6237autopilot_values = {}6238for i in range(attempts):6239self.drain_mav(quiet=True)6240self.drain_all_pexpects()6241received = set()6242for (name, value) in want.items():6243if verbose:6244self.progress("%s want=%f autopilot=%s (attempt=%u/%u)" %6245(name, value, autopilot_values.get(name, 'None'), i+1, attempts))6246if name not in autopilot_values:6247if verbose:6248self.progress("Requesting (%s)" % (name,))6249self.send_get_parameter_direct(name)6250continue6251delta = abs(autopilot_values[name] - value)6252if delta <= epsilon_pct*0.01*abs(value):6253# correct value6254self.progress("%s is now %f" % (name, autopilot_values[name]))6255if add_to_context:6256context_param_name_list = [p[0] for p in self.context_get().parameters]6257if name.upper() not in context_param_name_list:6258self.context_get().parameters.append((name, original_values[name]))6259received.add(name)6260continue6261self.progress("Sending set (%s) to (%f) (old=%f)" % (name, value, original_values[name]))6262self.send_set_parameter_direct(name, value)6263for name in received:6264del want[name]6265if len(want):6266# problem here is that a reboot can happen after we6267# send the request but before we receive the reply:6268try:6269self.do_timesync_roundtrip(quiet=True)6270except AutoTestTimeoutException:6271pass6272for m in param_value_messages:6273if m.param_id in want:6274self.progress("Received wanted PARAM_VALUE %s=%f" %6275(str(m.param_id), m.param_value))6276autopilot_values[m.param_id] = m.param_value6277if m.param_id not in original_values:6278original_values[m.param_id] = m.param_value6279param_value_messages = []62806281self.remove_message_hook(add_param_value)62826283if len(want) == 0:6284return6285raise ValueError("Failed to set parameters (%s)" % want)62866287def get_parameter(self, *args, **kwargs):6288return self.get_parameter_direct(*args, **kwargs)62896290def send_get_parameter_direct(self, name):6291encname = name6292if sys.version_info.major >= 3 and not isinstance(encname, bytes):6293encname = bytes(encname, 'ascii')6294self.mav.mav.param_request_read_send(self.sysid_thismav(),62951,6296encname,6297-1)62986299def get_parameter_direct(self, name, attempts=1, timeout=60, verbose=True, timeout_in_wallclock=False):6300while attempts > 0:6301attempts -= 16302if verbose:6303self.progress("Sending param_request_read for (%s)" % name)6304# we MUST parse here or collections fail where we need6305# them to work!6306self.drain_mav(quiet=True)6307if timeout_in_wallclock:6308tstart = time.time()6309else:6310tstart = self.get_sim_time()6311self.send_get_parameter_direct(name)6312while True:6313if timeout_in_wallclock:6314now = time.time()6315else:6316now = self.get_sim_time_cached()6317if tstart > now:6318self.progress("Time wrap detected")6319# we're going to have to send another request...6320break6321delta_time = now - tstart6322if delta_time > timeout:6323break6324m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)6325if verbose:6326self.progress("get_parameter(%s): %s" % (name, str(m), ))6327if m is None:6328continue6329if m.param_id == name:6330if delta_time > 5:6331self.progress("Long time to get parameter: %fs" % (delta_time,))6332return m.param_value6333if verbose:6334self.progress("(%s) != (%s)" % (m.param_id, name,))6335raise NotAchievedException("Failed to retrieve parameter (%s)" % name)63366337def get_parameter_mavproxy(self, mavproxy, name, attempts=1, timeout=60):6338"""Get parameters from vehicle."""6339for i in range(0, attempts):6340mavproxy.send("param fetch %s\n" % name)6341try:6342mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/attempts)6343try:6344# sometimes race conditions garble the MAVProxy output6345ret = float(mavproxy.match.group(1))6346except ValueError:6347continue6348return ret6349except pexpect.TIMEOUT:6350pass6351raise NotAchievedException("Failed to retrieve parameter (%s)" % name)63526353def get_parameters(self, some_list, **kwargs):6354ret = {}63556356for n in some_list:6357ret[n] = self.get_parameter(n, **kwargs)63586359return ret63606361def context_get(self):6362"""Get Saved parameters."""6363return self.contexts[-1]63646365def context_push(self):6366"""Save a copy of the parameters."""6367context = Context()6368self.contexts.append(context)6369# add a message hook so we can collect messages conveniently:63706371def mh(mav, m):6372t = m.get_type()6373if t in context.collections:6374context.collections[t].append(m)6375self.install_message_hook_context(mh)63766377def context_collect(self, msg_type):6378'''start collecting messages of type msg_type into context collection'''6379context = self.context_get()6380if msg_type in context.collections:6381return6382context.collections[msg_type] = []63836384def context_collection(self, msg_type):6385'''return messages in collection'''6386context = self.context_get()6387if msg_type not in context.collections:6388raise NotAchievedException("Not collecting (%s)" % str(msg_type))6389return context.collections[msg_type]63906391def context_clear_collection(self, msg_type):6392'''clear collection of message type msg_type'''6393context = self.context_get()6394if msg_type not in context.collections:6395raise NotAchievedException("Not collecting (%s)" % str(msg_type))6396context.collections[msg_type] = []63976398def context_stop_collecting(self, msg_type):6399'''stop collecting messages of type msg_type in context collection. Returns the collected messages'''6400context = self.context_get()6401if msg_type not in context.collections:6402raise Exception("Not collecting %s" % str(msg_type))6403ret = context.collections[msg_type]6404del context.collections[msg_type]6405return ret64066407def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False):6408"""Set parameters to origin values in reverse order."""6409dead = self.contexts.pop()6410# remove hooks first; these hooks can raise exceptions which6411# we really don't want...6412if not hooks_already_removed:6413for hook in dead.message_hooks:6414self.remove_message_hook(hook)6415for script in dead.installed_scripts:6416self.remove_installed_script(script)6417for (message_id, rate_hz) in dead.overridden_message_rates.items():6418self.set_message_rate_hz(message_id, rate_hz)6419for module in dead.installed_modules:6420print("Removing module (%s)" % module)6421self.remove_installed_modules(module)6422if dead.sitl_commandline_customised and len(self.contexts):6423self.contexts[-1].sitl_commandline_customised = True64246425dead_parameters_dict = {}6426for p in dead.parameters:6427dead_parameters_dict[p[0]] = p[1]6428if process_interaction_allowed:6429self.set_parameters(dead_parameters_dict, add_to_context=False)64306431if getattr(self, "old_binary", None) is not None:6432self.stop_SITL()6433with open(self.binary, "wb") as f:6434f.write(self.old_binary)6435f.close()6436self.start_SITL(wipe=False)6437self.set_streamrate(self.sitl_streamrate())6438elif dead.reboot_sitl_was_done:6439self.progress("Doing implicit context-pop reboot")6440self.reboot_sitl(mark_context=False)64416442# the following method is broken under Python2; can't **build_opts6443# def context_start_custom_binary(self, extra_defines={}):6444# # grab copy of current binary:6445# context = self.context_get()6446# if getattr(context, "old_binary", None) is not None:6447# raise ValueError("Not nestable at the moment")6448# with open(self.binary, "rb") as f:6449# self.old_binary = f.read()6450# f.close()6451# build_opts = copy.copy(self.build_opts)6452# build_opts["extra_defines"] = extra_defines6453# util.build_SITL(6454# 'bin/arducopter', # FIXME!6455# **build_opts,6456# )6457# self.stop_SITL()6458# self.start_SITL(wipe=False)6459# self.set_streamrate(self.sitl_streamrate())64606461class Context(object):6462def __init__(self, testsuite):6463self.testsuite = testsuite64646465def __enter__(self):6466self.testsuite.context_push()64676468def __exit__(self, type, value, traceback):6469self.testsuite.context_pop()6470return False # re-raise any exception64716472def sysid_thismav(self):6473return 164746475def create_MISSION_ITEM_INT(6476self,6477t,6478p1=0,6479p2=0,6480p3=0,6481p4=0,6482x=0,6483y=0,6484z=0,6485frame=mavutil.mavlink.MAV_FRAME_GLOBAL,6486autocontinue=0,6487current=0,6488target_system=1,6489target_component=1,6490seq=0,6491mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION,6492):6493return self.mav.mav.mission_item_int_encode(6494target_system,6495target_component,6496seq, # seq6497frame,6498t,6499current, # current6500autocontinue, # autocontinue6501p1, # p16502p2, # p26503p3, # p36504p4, # p46505x, # latitude6506y, # longitude6507z, # altitude6508mission_type6509)65106511def run_cmd_int(self,6512command,6513p1=0,6514p2=0,6515p3=0,6516p4=0,6517x=0,6518y=0,6519z=0,6520want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,6521timeout=10,6522target_sysid=None,6523target_compid=None,6524frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,6525p5=None,6526p6=None,6527p7=None,6528quiet=False,6529mav=None,6530):65316532if mav is None:6533mav = self.mav65346535if p5 is not None:6536x = p56537if p6 is not None:6538y = p66539if p7 is not None:6540z = p765416542if target_sysid is None:6543target_sysid = self.sysid_thismav()6544if target_compid is None:6545target_compid = 165466547self.get_sim_time() # required for timeout in run_cmd_get_ack to work65486549"""Send a MAVLink command int."""6550if not quiet:6551try:6552command_name = mavutil.mavlink.enums["MAV_CMD"][command].name6553except KeyError:6554command_name = "UNKNOWNu"6555self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f f=%u)" % (6556target_sysid,6557target_compid,6558command_name,6559command,6560p1,6561p2,6562p3,6563p4,6564x,6565y,6566z,6567frame6568))6569mav.mav.command_int_send(target_sysid,6570target_compid,6571frame,6572command,65730, # current65740, # autocontinue6575p1,6576p2,6577p3,6578p4,6579x,6580y,6581z)6582self.run_cmd_get_ack(command, want_result, timeout, mav=mav)65836584def send_cmd(self,6585command,6586p1=0,6587p2=0,6588p3=0,6589p4=0,6590p5=0,6591p6=0,6592p7=0,6593target_sysid=None,6594target_compid=None,6595mav=None,6596quiet=False,6597):6598"""Send a MAVLink command long."""6599if mav is None:6600mav = self.mav6601if target_sysid is None:6602target_sysid = self.sysid_thismav()6603if target_compid is None:6604target_compid = 16605if not quiet:6606try:6607command_name = mavutil.mavlink.enums["MAV_CMD"][command].name6608except KeyError:6609command_name = "UNKNOWN"6610self.progress("Sending COMMAND_LONG to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" %6611(6612target_sysid,6613target_compid,6614command_name,6615command,6616p1,6617p2,6618p3,6619p4,6620p5,6621p6,6622p7))6623mav.mav.command_long_send(target_sysid,6624target_compid,6625command,66261, # confirmation6627p1,6628p2,6629p3,6630p4,6631p5,6632p6,6633p7)66346635def run_cmd(self,6636command,6637p1=0,6638p2=0,6639p3=0,6640p4=0,6641p5=0,6642p6=0,6643p7=0,6644want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,6645target_sysid=None,6646target_compid=None,6647timeout=10,6648quiet=False,6649mav=None):6650self.drain_mav(mav=mav)6651self.get_sim_time() # required for timeout in run_cmd_get_ack to work6652self.send_cmd(6653command,6654p1,6655p2,6656p3,6657p4,6658p5,6659p6,6660p7,6661target_sysid=target_sysid,6662target_compid=target_compid,6663mav=mav,6664quiet=quiet,6665)6666self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet, mav=mav)66676668def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, ignore_in_progress=None):6669# note that the caller should ensure that this cached6670# timestamp is reasonably up-to-date!6671if mav is None:6672mav = self.mav6673if ignore_in_progress is None:6674ignore_in_progress = want_result != mavutil.mavlink.MAV_RESULT_IN_PROGRESS6675tstart = self.get_sim_time_cached()6676while True:6677if mav != self.mav:6678self.drain_mav()6679delta_time = self.get_sim_time_cached() - tstart6680if delta_time > timeout:6681raise AutoTestTimeoutException("Did not get good COMMAND_ACK within %fs" % timeout)6682m = mav.recv_match(type='COMMAND_ACK',6683blocking=True,6684timeout=0.1)6685if m is None:6686continue6687if not quiet:6688self.progress("ACK received: %s (%fs)" % (str(m), delta_time))6689if m.command == command:6690if m.result == mavutil.mavlink.MAV_RESULT_IN_PROGRESS and ignore_in_progress:6691continue6692if m.result != want_result:6693raise ValueError("Expected %s got %s" % (6694mavutil.mavlink.enums["MAV_RESULT"][want_result].name,6695mavutil.mavlink.enums["MAV_RESULT"][m.result].name))6696break66976698def set_current_waypoint_using_mav_cmd_do_set_mission_current(6699self,6700seq,6701reset=0,6702target_sysid=1,6703target_compid=1):6704self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,6705p1=seq,6706p2=reset,6707timeout=1,6708target_sysid=target_sysid,6709target_compid=target_compid)67106711def set_current_waypoint_using_mission_set_current(6712self,6713seq,6714target_sysid=1,6715target_compid=1,6716check_afterwards=True):6717self.mav.mav.mission_set_current_send(target_sysid,6718target_compid,6719seq)6720if check_afterwards:6721self.wait_current_waypoint(seq, timeout=10)67226723def set_current_waypoint(self, seq, target_sysid=1, target_compid=1, check_afterwards=True):6724return self.set_current_waypoint_using_mission_set_current(6725seq,6726target_sysid,6727target_compid,6728check_afterwards=check_afterwards6729)67306731def verify_parameter_values(self, parameter_stuff, max_delta=0.0):6732bad = ""6733for param in parameter_stuff:6734fetched_value = self.get_parameter(param)6735wanted_value = parameter_stuff[param]6736if isinstance(wanted_value, tuple):6737max_delta = wanted_value[1]6738wanted_value = wanted_value[0]6739if abs(fetched_value - wanted_value) > max_delta:6740bad += "%s=%f (want=%f +/-%f) " % (param, fetched_value, wanted_value, max_delta)6741if len(bad):6742raise NotAchievedException("Bad parameter values: %s" %6743(bad,))67446745#################################################6746# UTILITIES6747#################################################6748def lineno(self):6749'''return line number'''6750frameinfo = getframeinfo(currentframe().f_back)6751# print(frameinfo.filename, frameinfo.lineno)6752return frameinfo.lineno67536754@staticmethod6755def longitude_scale(lat):6756ret = math.cos(lat * (math.radians(1)))6757print("scale=%f" % ret)6758return ret67596760@staticmethod6761def get_distance(loc1, loc2):6762"""Get ground distance between two locations."""6763return TestSuite.get_distance_accurate(loc1, loc2)6764# dlat = loc2.lat - loc1.lat6765# try:6766# dlong = loc2.lng - loc1.lng6767# except AttributeError:6768# dlong = loc2.lon - loc1.lon67696770# return math.sqrt((dlat*dlat) + (dlong*dlong)*TestSuite.longitude_scale(loc2.lat)) * 1.113195e567716772@staticmethod6773def get_distance_accurate(loc1, loc2):6774"""Get ground distance between two locations."""6775try:6776lon1 = loc1.lng6777lon2 = loc2.lng6778except AttributeError:6779lon1 = loc1.lon6780lon2 = loc2.lon67816782return mp_util.gps_distance(loc1.lat, lon1, loc2.lat, lon2)67836784def assert_distance(self, loc1, loc2, min_distance, max_distance):6785dist = self.get_distance_accurate(loc1, loc2)6786if dist < min_distance or dist > max_distance:6787raise NotAchievedException("Expected distance %f to be between %f and %f" %6788(dist, min_distance, max_distance))6789self.progress("Distance %f is between %f and %f" %6790(dist, min_distance, max_distance))67916792@staticmethod6793def get_latlon_attr(loc, attrs):6794'''return any found latitude attribute from loc'''6795ret = None6796for attr in attrs:6797if hasattr(loc, attr):6798ret = getattr(loc, attr)6799break6800if ret is None:6801raise ValueError("None of %s in loc(%s)" % (str(attrs), str(loc)))6802return ret68036804@staticmethod6805def get_lat_attr(loc):6806'''return any found latitude attribute from loc'''6807return TestSuite.get_latlon_attr(loc, ["lat", "latitude"])68086809@staticmethod6810def get_lon_attr(loc):6811'''return any found latitude attribute from loc'''6812return TestSuite.get_latlon_attr(loc, ["lng", "lon", "longitude"])68136814@staticmethod6815def get_distance_int(loc1, loc2):6816"""Get ground distance between two locations in the normal "int" form6817- lat/lon multiplied by 1e7"""6818loc1_lat = TestSuite.get_lat_attr(loc1)6819loc2_lat = TestSuite.get_lat_attr(loc2)6820loc1_lon = TestSuite.get_lon_attr(loc1)6821loc2_lon = TestSuite.get_lon_attr(loc2)68226823return TestSuite.get_distance_accurate(6824mavutil.location(loc1_lat*1e-7, loc1_lon*1e-7),6825mavutil.location(loc2_lat*1e-7, loc2_lon*1e-7))68266827# dlat = loc2_lat - loc1_lat6828# dlong = loc2_lon - loc1_lon6829#6830# dlat /= 10000000.06831# dlong /= 10000000.06832#6833# return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e568346835def bearing_to(self, loc):6836'''return bearing from here to location'''6837here = self.mav.location()6838return self.get_bearing(here, loc)68396840@staticmethod6841def get_bearing(loc1, loc2):6842"""Get bearing from loc1 to loc2."""6843off_x = loc2.lng - loc1.lng6844off_y = loc2.lat - loc1.lat6845bearing = 90.00 + math.atan2(-off_y, off_x) * 57.29577956846if bearing < 0:6847bearing += 360.006848return bearing68496850def send_cmd_do_set_mode(self, mode):6851self.send_cmd(6852mavutil.mavlink.MAV_CMD_DO_SET_MODE,6853p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,6854p2=self.get_mode_from_mode_mapping(mode),6855)68566857def assert_mode(self, mode):6858self.wait_mode(mode, timeout=0)68596860def change_mode(self, mode, timeout=60):6861'''change vehicle flightmode'''6862self.wait_heartbeat()6863self.progress("Changing mode to %s" % mode)6864self.send_cmd_do_set_mode(mode)6865tstart = self.get_sim_time()6866while not self.mode_is(mode):6867custom_num = self.mav.messages['HEARTBEAT'].custom_mode6868self.progress("mav.flightmode=%s Want=%s custom=%u" % (6869self.mav.flightmode, mode, custom_num))6870if (timeout is not None and6871self.get_sim_time_cached() > tstart + timeout):6872raise WaitModeTimeout("Did not change mode")6873self.send_cmd_do_set_mode(mode)6874self.progress("Got mode %s" % mode)68756876def capable(self, capability):6877return self.get_autopilot_capabilities() & capability68786879def assert_capability(self, capability):6880if not self.capable(capability):6881name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name6882raise NotAchievedException("AutoPilot does not have capbility %s" % (name,))68836884def assert_no_capability(self, capability):6885if self.capable(capability):6886name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name6887raise NotAchievedException("AutoPilot has feature %s (when it shouln't)" % (name,))68886889def get_autopilot_capabilities(self):6890# Cannot use run_cmd otherwise the respond is lost during the wait for ACK6891self.mav.mav.command_long_send(self.sysid_thismav(),68921,6893mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,68940, # confirmation68951, # 1: Request autopilot version68960,68970,68980,68990,69000,69010)6902m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)6903return m.capabilities69046905def decode_flight_sw_version(self, flight_sw_version: int):6906""" Decode 32 bit flight_sw_version mavlink parameter6907corresponds to encoding in ardupilot GCS_MAVLINK::send_autopilot_version."""6908fw_type_id = (flight_sw_version >> 0) % 2566909patch = (flight_sw_version >> 8) % 2566910minor = (flight_sw_version >> 16) % 2566911major = (flight_sw_version >> 24) % 2566912if fw_type_id == 0:6913fw_type = "dev"6914elif fw_type_id == 64:6915fw_type = "alpha"6916elif fw_type_id == 128:6917fw_type = "beta"6918elif fw_type_id == 192:6919fw_type = "rc"6920elif fw_type_id == 255:6921fw_type = "official"6922else:6923fw_type = "undefined"6924return major, minor, patch, fw_type69256926def get_autopilot_firmware_version(self):6927self.mav.mav.command_long_send(self.sysid_thismav(),69281,6929mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,69300, # confirmation69311, # 1: Request autopilot version69320,69330,69340,69350,69360,69370)6938m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)6939self.fcu_firmware_version = self.decode_flight_sw_version(m.flight_sw_version)69406941def hex_values_to_int(hex_values):6942# Convert ascii codes to characters6943hex_chars = [chr(int(hex_value)) for hex_value in hex_values]6944# Convert hex characters to integers, handle \x00 case6945int_values = [0 if hex_char == '\x00' else int(hex_char, 16) for hex_char in hex_chars]6946return int_values69476948fcu_hash_to_hex = ""6949for i in hex_values_to_int(m.flight_custom_version):6950fcu_hash_to_hex += f"{i:x}"6951self.fcu_firmware_hash = fcu_hash_to_hex6952self.progress(f"Firmware Version {self.fcu_firmware_version}")6953self.progress(f"Firmware hash {self.fcu_firmware_hash}")6954self.githash = util.get_git_hash(short=True)6955self.progress(f"Git hash {self.githash}")69566957def GetCapabilities(self):6958'''Get Capabilities'''6959self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT)6960self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION)69616962def get_mode_from_mode_mapping(self, mode):6963"""Validate and return the mode number from a string or int."""6964if isinstance(mode, int):6965return mode6966mode_map = self.mav.mode_mapping()6967if mode_map is None:6968mav_type = self.mav.messages['HEARTBEAT'].type6969mav_autopilot = self.mav.messages['HEARTBEAT'].autopilot6970raise ErrorException("No mode map for (mav_type=%s mav_autopilot=%s)" % (mav_type, mav_autopilot))6971if isinstance(mode, str):6972if mode in mode_map:6973return mode_map.get(mode)6974if mode in mode_map.values():6975return mode6976self.progress("No mode (%s); available modes '%s'" % (mode, mode_map))6977raise ErrorException("Unknown mode '%s'" % mode)69786979def get_mode_string_for_mode(self, mode):6980if isinstance(mode, str):6981return mode6982mode_map = self.mav.mode_mapping()6983if mode_map is None:6984return f"mode={mode}"6985for (n, v) in mode_map.items():6986if v == mode:6987return n6988self.progress(f"No mode ({mode} {type(mode)}); available modes '{mode_map}'")6989raise ErrorException("Unknown mode '%s'" % mode)69906991def run_cmd_do_set_mode(self,6992mode,6993timeout=30,6994run_cmd=None,6995want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):6996if run_cmd is None:6997run_cmd = self.run_cmd6998base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED6999custom_mode = self.get_mode_from_mode_mapping(mode)7000run_cmd(7001mavutil.mavlink.MAV_CMD_DO_SET_MODE,7002p1=base_mode,7003p2=custom_mode,7004want_result=want_result,7005timeout=timeout,7006)70077008def do_set_mode_via_command_XYZZY(self, mode, run_cmd, timeout=30):7009"""Set mode with a command long message."""7010tstart = self.get_sim_time()7011want_custom_mode = self.get_mode_from_mode_mapping(mode)7012while True:7013remaining = timeout - (self.get_sim_time_cached() - tstart)7014if remaining <= 0:7015raise AutoTestTimeoutException("Failed to change mode")7016self.run_cmd_do_set_mode(mode, run_cmd=run_cmd, timeout=10)7017m = self.wait_heartbeat()7018self.progress("Got mode=%u want=%u" % (m.custom_mode, want_custom_mode))7019if m.custom_mode == want_custom_mode:7020return70217022def do_set_mode_via_command_long(self, mode, timeout=30):7023self.do_set_mode_via_command_XYZZY(mode, self.run_cmd, timeout=timeout)70247025def do_set_mode_via_command_int(self, mode, timeout=30):7026self.do_set_mode_via_command_XYZZY(mode, self.run_cmd_int, timeout=timeout)70277028def mavproxy_do_set_mode_via_command_long(self, mavproxy, mode, timeout=30):7029"""Set mode with a command long message with Mavproxy."""7030base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED7031custom_mode = self.get_mode_from_mode_mapping(mode)7032tstart = self.get_sim_time()7033while True:7034remaining = timeout - (self.get_sim_time_cached() - tstart)7035if remaining <= 0:7036raise AutoTestTimeoutException("Failed to change mode")7037mavproxy.send("long DO_SET_MODE %u %u\n" %7038(base_mode, custom_mode))7039m = self.wait_heartbeat()7040if m.custom_mode == custom_mode:7041return True70427043def reach_heading_manual(self, heading, turn_right=True):7044"""Manually direct the vehicle to the target heading."""7045if self.is_copter() or self.is_sub():7046self.set_rc(4, 1580)7047self.wait_heading(heading)7048self.set_rc(4, 1500)7049if self.is_plane():7050self.set_rc(1, 1800)7051self.wait_heading(heading)7052self.set_rc(1, 1500)7053if self.is_rover():7054steering_pwm = 17007055if not turn_right:7056steering_pwm = 13007057self.set_rc(1, steering_pwm)7058self.set_rc(3, 1550)7059self.wait_heading(heading)7060self.set_rc(3, 1500)7061self.set_rc(1, 1500)70627063def assert_vehicle_location_is_at_startup_location(self, dist_max=1):7064here = self.mav.location()7065start_loc = self.sitl_start_location()7066dist = self.get_distance(here, start_loc)7067data = "dist=%f max=%f (here: %s start-loc: %s)" % (dist, dist_max, here, start_loc)70687069if dist > dist_max:7070raise NotAchievedException("Far from startup location: %s" % data)7071self.progress("Close to startup location: %s" % data)70727073def assert_simstate_location_is_at_startup_location(self, dist_max=1):7074simstate_loc = self.sim_location()7075start_loc = self.sitl_start_location()7076dist = self.get_distance(simstate_loc, start_loc)7077data = "dist=%f max=%f (simstate: %s start-loc: %s)" % (dist, dist_max, simstate_loc, start_loc)70787079if dist > dist_max:7080raise NotAchievedException("simstate far from startup location: %s" % data)7081self.progress("Simstate Close to startup location: %s" % data)70827083def reach_distance_manual(self, distance):7084"""Manually direct the vehicle to the target distance from home."""7085if self.is_copter():7086self.set_rc(2, 1350)7087self.wait_distance(distance, accuracy=5, timeout=60)7088self.set_rc(2, 1500)7089if self.is_plane():7090self.progress("NOT IMPLEMENTED")7091if self.is_rover():7092self.set_rc(3, 1700)7093self.wait_distance(distance, accuracy=2)7094self.set_rc(3, 1500)70957096def guided_achieve_heading(self, heading, accuracy=None):7097tstart = self.get_sim_time()7098while True:7099if self.get_sim_time_cached() - tstart > 200:7100raise NotAchievedException("Did not achieve heading")7101self.run_cmd(7102mavutil.mavlink.MAV_CMD_CONDITION_YAW,7103p1=heading, # target angle7104p2=10, # degrees/second7105p3=1, # -1 is counter-clockwise, 1 clockwise7106p4=0, # 1 for relative, 0 for absolute7107)7108m = self.mav.recv_match(type='VFR_HUD', blocking=True)7109self.progress("heading=%d want=%d" % (m.heading, int(heading)))7110if accuracy is not None:7111delta = abs(m.heading - int(heading))7112if delta <= accuracy:7113return7114if m.heading == int(heading):7115return71167117def assert_heading(self, heading, accuracy=1):7118'''assert vehicle yaw is to heading (0-360)'''7119m = self.assert_receive_message('VFR_HUD')7120if self.heading_delta(heading, m.heading) > accuracy:7121raise NotAchievedException("Unexpected heading=%f want=%f" %7122(m.heading, heading))71237124def do_set_relay(self, relay_num, on_off, timeout=10):7125"""Set relay with a command long message."""7126self.progress("Set relay %d to %d" % (relay_num, on_off))7127self.run_cmd(7128mavutil.mavlink.MAV_CMD_DO_SET_RELAY,7129p1=relay_num,7130p2=on_off,7131timeout=timeout,7132)71337134def do_set_relay_mavproxy(self, relay_num, on_off):7135"""Set relay with mavproxy."""7136self.progress("Set relay %d to %d" % (relay_num, on_off))7137self.mavproxy.send('module load relay\n')7138self.mavproxy.expect("Loaded module relay")7139self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off))71407141def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7142self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result)71437144def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7145self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result)71467147def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7148self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result)71497150def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7151self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result)71527153#################################################7154# WAIT UTILITIES7155#################################################7156def delay_sim_time(self, seconds_to_wait, reason=None):7157"""Wait some second in SITL time."""7158tstart = self.get_sim_time()7159tnow = tstart7160r = "Delaying %f seconds"7161if reason is not None:7162r += " for %s" % reason7163self.progress(r % (seconds_to_wait,))7164while tstart + seconds_to_wait > tnow:7165tnow = self.get_sim_time(drain_mav=False)71667167def send_terrain_check_message(self):7168here = self.mav.location()7169self.mav.mav.terrain_check_send(int(here.lat * 1e7), int(here.lng * 1e7))71707171def get_terrain_height(self, verbose=False):7172self.send_terrain_check_message()7173m = self.assert_receive_message('TERRAIN_REPORT', very_verbose=True)7174return m.terrain_height71757176def get_altitude(self, relative=False, timeout=30, altitude_source=None):7177'''returns vehicles altitude in metres, possibly relative-to-home'''7178if altitude_source is None:7179if relative:7180altitude_source = "GLOBAL_POSITION_INT.relative_alt"7181else:7182altitude_source = "GLOBAL_POSITION_INT.alt"7183if altitude_source == "TERRAIN_REPORT.current_height":7184terrain = self.assert_receive_message('TERRAIN_REPORT')7185return terrain.current_height71867187(msg, field) = altitude_source.split('.')7188msg = self.poll_message(msg, quiet=True)7189divisor = 1000.0 # mm is pretty common in mavlink7190if altitude_source == "SIM_STATE.alt":7191divisor = 1.07192return getattr(msg, field) / divisor71937194def assert_altitude(self, alt, accuracy=1, **kwargs):7195got_alt = self.get_altitude(**kwargs)7196if abs(alt - got_alt) > accuracy:7197raise NotAchievedException("Incorrect alt; want=%f got=%f" %7198(alt, got_alt))71997200def assert_rangefinder_distance_between(self, dist_min, dist_max):7201m = self.assert_receive_message('RANGEFINDER')72027203if m.distance < dist_min:7204raise NotAchievedException("below min height (%f < %f)" %7205(m.distance, dist_min))72067207if m.distance > dist_max:7208raise NotAchievedException("above max height (%f > %f)" %7209(m.distance, dist_max))72107211def assert_distance_sensor_quality(self, quality):7212m = self.assert_receive_message('DISTANCE_SENSOR')72137214if m.signal_quality != quality:7215raise NotAchievedException("Unexpected quality; want=%f got=%f" %7216(quality, m.signal_quality))72177218def get_rangefinder_distance(self):7219m = self.assert_receive_message('RANGEFINDER', timeout=5)7220return m.distance72217222def wait_rangefinder_distance(self, dist_min, dist_max, timeout=30, **kwargs):7223'''wait for RANGEFINDER distance'''7224def validator(value2, target2=None):7225if dist_min <= value2 <= dist_max:7226return True7227else:7228return False72297230self.wait_and_maintain(7231value_name="RageFinderDistance",7232target=dist_min,7233current_value_getter=lambda: self.get_rangefinder_distance(),7234accuracy=(dist_max - dist_min),7235validator=lambda value2, target2: validator(value2, target2),7236timeout=timeout,7237**kwargs7238)72397240def get_esc_rpm(self, esc):7241if esc > 4:7242raise ValueError("Only does 1-4")7243m = self.assert_receive_message('ESC_TELEMETRY_1_TO_4', timeout=1, verbose=True)7244return m.rpm[esc-1]72457246def find_first_set_bit(self, mask):7247'''returns offset of first-set-bit (counting from right) in mask. Returns None if no bits set'''7248pos = 07249while mask != 0:7250if mask & 0x1:7251return pos7252mask = mask >> 17253pos += 17254return None72557256def get_rpm(self, rpm_sensor):7257m = self.assert_receive_message('RPM')7258if rpm_sensor == 1:7259ret = m.rpm17260elif rpm_sensor == 2:7261ret = m.rpm27262else:7263raise ValueError("Bad sensor id")7264if ret < 0.000001:7265# yay filtering!7266return 07267return ret72687269def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs):7270'''wait for RPM to be between rpm_min and rpm_max'''7271def validator(value2, target2=None):7272return rpm_min <= value2 <= rpm_max7273self.wait_and_maintain(7274value_name="RPM%u" % rpm_sensor,7275target=(rpm_min+rpm_max)/2.0,7276current_value_getter=lambda: self.get_rpm(rpm_sensor),7277accuracy=rpm_max-rpm_min,7278validator=lambda value2, target2: validator(value2, target2),7279**kwargs7280)72817282def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):7283'''wait for ESC to be between rpm_min and rpm_max'''7284def validator(value2, target2=None):7285return rpm_min <= value2 <= rpm_max7286self.wait_and_maintain(7287value_name="ESC %u RPM" % esc,7288target=(rpm_min+rpm_max)/2.0,7289current_value_getter=lambda: self.get_esc_rpm(esc),7290accuracy=rpm_max-rpm_min,7291validator=lambda value2, target2: validator(value2, target2),7292**kwargs7293)72947295def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=None, **kwargs):7296"""Wait for a given altitude range."""7297assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude."72987299if timeout is None:7300timeout = 3073017302def validator(value2, target2=None):7303if altitude_min <= value2 <= altitude_max:7304return True7305else:7306return False73077308altitude_source = kwargs.get("altitude_source", None)73097310self.wait_and_maintain(7311value_name="Altitude",7312target=(altitude_min + altitude_max)*0.5,7313current_value_getter=lambda: self.get_altitude(7314relative=relative,7315timeout=timeout,7316altitude_source=altitude_source,7317),7318accuracy=(altitude_max - altitude_min)*0.5,7319validator=lambda value2, target2: validator(value2, target2),7320timeout=timeout,7321**kwargs7322)73237324def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True, altitude_source=None):7325"""Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration"""7326return self.wait_altitude(7327altitude_min=altitude_min,7328altitude_max=altitude_max,7329relative=relative,7330minimum_duration=minimum_duration,7331timeout=minimum_duration + 1,7332altitude_source=altitude_source,7333)73347335def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):7336"""Wait for a given vertical rate."""7337assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."73387339def get_climbrate(timeout2):7340msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)7341return msg.climb73427343def validator(value2, target2=None):7344if speed_min <= value2 <= speed_max:7345return True7346else:7347return False73487349self.wait_and_maintain(7350value_name="Climbrate",7351target=speed_min,7352current_value_getter=lambda: get_climbrate(timeout),7353accuracy=(speed_max - speed_min),7354validator=lambda value2, target2: validator(value2, target2),7355timeout=timeout,7356**kwargs7357)73587359def groundspeed(self):7360m = self.assert_receive_message('VFR_HUD')7361return m.groundspeed73627363def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs):7364self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs)73657366def wait_airspeed(self, speed_min, speed_max, timeout=30, **kwargs):7367self.wait_vfr_hud_speed("airspeed", speed_min, speed_max, timeout=timeout, **kwargs)73687369def wait_vfr_hud_speed(self, field, speed_min, speed_max, timeout=30, **kwargs):7370"""Wait for a given ground speed range."""7371assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."73727373def get_speed(timeout2):7374msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)7375return getattr(msg, field)73767377self.wait_and_maintain_range(7378value_name=field,7379minimum=speed_min,7380maximum=speed_max,7381current_value_getter=lambda: get_speed(timeout),7382validator=None,7383timeout=timeout,7384**kwargs7385)73867387def wait_roll(self, roll, accuracy, timeout=30, **kwargs):7388"""Wait for a given roll in degrees."""7389def get_roll(timeout2):7390msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7391p = math.degrees(msg.pitch)7392r = math.degrees(msg.roll)7393self.progress("Roll %d Pitch %d" % (r, p))7394return r73957396def validator(value2, target2):7397return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy73987399self.wait_and_maintain(7400value_name="Roll",7401target=roll,7402current_value_getter=lambda: get_roll(timeout),7403validator=lambda value2, target2: validator(value2, target2),7404accuracy=accuracy,7405timeout=timeout,7406**kwargs7407)74087409def wait_pitch(self, pitch, accuracy, timeout=30, **kwargs):7410"""Wait for a given pitch in degrees."""7411def get_pitch(timeout2):7412msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7413p = math.degrees(msg.pitch)7414r = math.degrees(msg.roll)7415self.progress("Pitch %d Roll %d" % (p, r))7416return p74177418def validator(value2, target2):7419return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy74207421self.wait_and_maintain(7422value_name="Pitch",7423target=pitch,7424current_value_getter=lambda: get_pitch(timeout),7425validator=lambda value2, target2: validator(value2, target2),7426accuracy=accuracy,7427timeout=timeout,7428**kwargs7429)74307431def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs):7432if isinstance(target, Vector3):7433return self.wait_and_maintain_vector(7434value_name,7435target,7436current_value_getter,7437validator,7438timeout=30,7439**kwargs7440)7441return self.wait_and_maintain_range(7442value_name,7443minimum=target - accuracy,7444maximum=target + accuracy,7445current_value_getter=current_value_getter,7446validator=validator,7447timeout=timeout,7448print_diagnostics_as_target_not_range=True,7449**kwargs7450)74517452def wait_and_maintain_vector(self,7453value_name,7454target,7455current_value_getter,7456validator,7457timeout=30,7458**kwargs):7459tstart = self.get_sim_time()7460achieving_duration_start = None7461sum_of_achieved_values = Vector3()7462last_value = Vector3()7463last_fail_print = 07464count_of_achieved_values = 07465called_function = kwargs.get("called_function", None)7466minimum_duration = kwargs.get("minimum_duration", 0)7467if minimum_duration >= timeout:7468raise ValueError("minimum_duration >= timeout")74697470self.progress("Waiting for %s=(%s)" % (value_name, str(target)))74717472last_print_time = 07473while True: # if we failed to received message with the getter the sim time isn't updated # noqa7474now = self.get_sim_time_cached()7475if now - tstart > timeout:7476raise AutoTestTimeoutException(7477"Failed to attain %s want %s, reached %s" %7478(value_name,7479str(target),7480str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) # noqa74817482last_value = current_value_getter()7483if called_function is not None:7484called_function(last_value, target)7485is_value_valid = validator(last_value, target)7486if self.get_sim_time_cached() - last_print_time > 1:7487if is_value_valid:7488want_or_got = "got"7489else:7490want_or_got = "want"7491achieved_duration_bit = ""7492if achieving_duration_start is not None:7493so_far = self.get_sim_time_cached() - achieving_duration_start7494achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)7495self.progress(7496"%s=(%s) (%s (%s))%s" %7497(value_name,7498str(last_value),7499want_or_got,7500str(target),7501achieved_duration_bit)7502)7503last_print_time = self.get_sim_time_cached()7504if is_value_valid:7505sum_of_achieved_values += last_value7506count_of_achieved_values += 1.07507if achieving_duration_start is None:7508achieving_duration_start = self.get_sim_time_cached()7509if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:7510self.progress("Attained %s=%s" % (7511value_name,7512str(sum_of_achieved_values * (1.0 / count_of_achieved_values))))7513return True7514else:7515achieving_duration_start = None7516sum_of_achieved_values.zero()7517count_of_achieved_values = 07518if now - last_fail_print > 1:7519self.progress("Waiting for (%s), got %s" %7520(target, last_value))7521last_fail_print = now75227523def validate_kwargs(self, kwargs, valid={}):7524for key in kwargs:7525if key not in valid:7526raise NotAchievedException("Invalid kwarg %s" % str(key))75277528def wait_and_maintain_range(self,7529value_name,7530minimum,7531maximum,7532current_value_getter,7533validator=None,7534value_averager=None,7535timeout=30,7536print_diagnostics_as_target_not_range=False,7537**kwargs):7538self.validate_kwargs(kwargs, valid=frozenset([7539"called_function",7540"minimum_duration",7541"altitude_source",7542]))75437544if print_diagnostics_as_target_not_range:7545target = (minimum + maximum) / 27546accuracy = (maximum - minimum) / 27547tstart = self.get_sim_time()7548achieving_duration_start = None7549sum_of_achieved_values = 0.07550last_value = 0.07551count_of_achieved_values = 07552called_function = kwargs.get("called_function", None)7553minimum_duration = kwargs.get("minimum_duration", 0)7554if minimum_duration >= timeout:7555raise ValueError("minimum_duration >= timeout")7556if print_diagnostics_as_target_not_range:7557self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy))7558else:7559self.progress("Waiting for %s between (%s) and (%s)" % (value_name, str(minimum), str(maximum)))7560last_print_time = 07561while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa7562last_value = current_value_getter()7563if called_function is not None:7564if print_diagnostics_as_target_not_range:7565called_function(last_value, target)7566else:7567called_function(last_value, minimum, maximum)7568if validator is not None:7569if print_diagnostics_as_target_not_range:7570is_value_valid = validator(last_value, target)7571else:7572is_value_valid = validator(last_value, minimum, maximum)7573else:7574is_value_valid = (minimum <= last_value) and (last_value <= maximum)7575if self.get_sim_time_cached() - last_print_time > 1:7576if is_value_valid:7577want_or_got = "got"7578else:7579want_or_got = "want"7580achieved_duration_bit = ""7581if achieving_duration_start is not None:7582so_far = self.get_sim_time_cached() - achieving_duration_start7583achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)75847585if print_diagnostics_as_target_not_range:7586self.progress(7587"%s=%0.2f (%s %f +- %f)%s" %7588(value_name,7589last_value,7590want_or_got,7591target,7592accuracy,7593achieved_duration_bit)7594)7595else:7596if isinstance(last_value, float):7597self.progress(7598"%s=%0.2f (%s between %s and %s)%s" %7599(value_name,7600last_value,7601want_or_got,7602str(minimum),7603str(maximum),7604achieved_duration_bit)7605)7606else:7607self.progress(7608"%s=%s (%s between %s and %s)%s" %7609(value_name,7610last_value,7611want_or_got,7612str(minimum),7613str(maximum),7614achieved_duration_bit)7615)7616last_print_time = self.get_sim_time_cached()7617if is_value_valid:7618if value_averager is not None:7619average = value_averager.add_value(last_value)7620else:7621sum_of_achieved_values += last_value7622count_of_achieved_values += 1.07623average = sum_of_achieved_values / count_of_achieved_values7624if achieving_duration_start is None:7625achieving_duration_start = self.get_sim_time_cached()7626if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:7627self.progress("Attained %s=%s" % (value_name, average))7628return True7629else:7630achieving_duration_start = None7631sum_of_achieved_values = 0.07632count_of_achieved_values = 07633if value_averager is not None:7634value_averager.reset()7635if print_diagnostics_as_target_not_range:7636raise AutoTestTimeoutException(7637"Failed to attain %s want %s, reached %s" %7638(value_name,7639str(target),7640str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))7641else:7642raise AutoTestTimeoutException(7643"Failed to attain %s between %s and %s, reached %s" %7644(value_name,7645str(minimum),7646str(maximum),7647str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))76487649def heading_delta(self, heading1, heading2):7650'''return angle between two 0-360 headings'''7651return math.fabs((heading1 - heading2 + 180) % 360 - 180)76527653def get_heading(self, timeout=1):7654'''return heading 0-359'''7655m = self.assert_receive_message('VFR_HUD', timeout=timeout)7656return m.heading76577658def wait_heading(self, heading, accuracy=5, timeout=30, **kwargs):7659"""Wait for a given heading."""7660def get_heading_wrapped(timeout2):7661return self.get_heading(timeout=timeout2)76627663def validator(value2, target2):7664return self.heading_delta(value2, target2) <= accuracy76657666self.wait_and_maintain(7667value_name="Heading",7668target=heading,7669current_value_getter=lambda: get_heading_wrapped(timeout),7670validator=lambda value2, target2: validator(value2, target2),7671accuracy=accuracy,7672timeout=timeout,7673**kwargs7674)76757676def wait_yaw_speed(self, yaw_speed, accuracy=0.1, timeout=30, **kwargs):7677"""Wait for a given yaw speed in radians per second."""7678def get_yawspeed(timeout2):7679msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7680return msg.yawspeed76817682def validator(value2, target2):7683return math.fabs(value2 - target2) <= accuracy76847685self.wait_and_maintain(7686value_name="YawSpeed",7687target=yaw_speed,7688current_value_getter=lambda: get_yawspeed(timeout),7689validator=lambda value2, target2: validator(value2, target2),7690accuracy=accuracy,7691timeout=timeout,7692**kwargs7693)76947695def get_speed_vector(self, timeout=1):7696'''return speed vector, NED'''7697msg = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)7698return Vector3(msg.vx, msg.vy, msg.vz)76997700"""Wait for a given speed vector."""7701def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs):7702def validator(value2, target2):7703for (want, got) in (target2.x, value2.x), (target2.y, value2.y), (target2.z, value2.z):7704if want != float("nan") and (math.fabs(got - want) > accuracy):7705return False7706return True77077708self.wait_and_maintain(7709value_name="SpeedVector",7710target=speed_vector,7711current_value_getter=lambda: self.get_speed_vector(timeout=timeout),7712validator=lambda value2, target2: validator(value2, target2),7713accuracy=accuracy,7714timeout=timeout,7715**kwargs7716)77177718def get_descent_rate(self):7719'''get descent rate - a positive number if you are going down'''7720return abs(self.get_speed_vector().z)77217722def wait_descent_rate(self, rate, accuracy=0.1, **kwargs):7723'''wait for descent rate rate, a positive number if going down'''7724def validator(value, target):7725return math.fabs(value - target) <= accuracy77267727self.wait_and_maintain(7728value_name="DescentRate",7729target=rate,7730current_value_getter=lambda: self.get_descent_rate(),7731validator=lambda value, target: validator(value, target),7732accuracy=accuracy,7733**kwargs7734)77357736def get_body_frame_velocity(self):7737gri = self.assert_receive_message('GPS_RAW_INT', timeout=1)7738att = self.assert_receive_message('ATTITUDE', timeout=1)7739return mavextra.gps_velocity_body(gri, att)77407741def wait_speed_vector_bf(self, speed_vector, accuracy=0.2, timeout=30, **kwargs):7742"""Wait for a given speed vector."""7743def get_speed_vector(timeout2):7744return self.get_body_frame_velocity()77457746def validator(value2, target2):7747return (math.fabs(value2.x - target2.x) <= accuracy and7748math.fabs(value2.y - target2.y) <= accuracy and7749math.fabs(value2.z - target2.z) <= accuracy)77507751self.wait_and_maintain(7752value_name="SpeedVectorBF",7753target=speed_vector,7754current_value_getter=lambda: get_speed_vector(timeout),7755validator=lambda value2, target2: validator(value2, target2),7756accuracy=accuracy,7757timeout=timeout,7758**kwargs7759)77607761def wait_distance_between(self, series1, series2, min_distance, max_distance, timeout=30, **kwargs):7762"""Wait for distance between two position series to be between two thresholds."""7763def get_distance():7764self.drain_mav()7765m1 = self.mav.messages[series1]7766m2 = self.mav.messages[series2]7767return self.get_distance_int(m1, m2)77687769self.wait_and_maintain_range(7770value_name=f"Distance({series1}, {series2})",7771minimum=min_distance,7772maximum=max_distance,7773current_value_getter=lambda: get_distance(),7774timeout=timeout,7775**kwargs7776)77777778def wait_distance(self, distance, accuracy=2, timeout=30, **kwargs):7779"""Wait for flight of a given distance."""7780start = self.mav.location()77817782def get_distance():7783return self.get_distance(start, self.mav.location())77847785def validator(value2, target2):7786return math.fabs(value2 - target2) <= accuracy77877788self.wait_and_maintain(7789value_name="Distance",7790target=distance,7791current_value_getter=lambda: get_distance(),7792validator=lambda value2, target2: validator(value2, target2),7793accuracy=accuracy,7794timeout=timeout,7795**kwargs7796)77977798def wait_distance_to_waypoint(self, wp_num, distance_min, distance_max, **kwargs):7799# TODO: use mission_request_partial_list_send7800wps = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)7801m = wps[wp_num]7802self.progress("m: %s" % str(m))7803loc = mavutil.location(m.x / 1.0e7, m.y / 1.0e7, 0, 0)7804self.progress("loc: %s" % str(loc))7805self.wait_distance_to_location(loc, distance_min, distance_max, **kwargs)78067807def wait_distance_to_location(self, location, distance_min, distance_max, timeout=30, **kwargs):7808"""Wait for flight of a given distance."""7809assert distance_min <= distance_max, "Distance min should be less than distance max."78107811def get_distance():7812return self.get_distance(location, self.mav.location())78137814def validator(value2, target2=None):7815return distance_min <= value2 <= distance_max78167817self.wait_and_maintain(7818value_name="Distance",7819target=distance_min,7820current_value_getter=lambda: get_distance(),7821validator=lambda value2, target2: validator(value2, target2),7822accuracy=(distance_max - distance_min), timeout=timeout,7823**kwargs7824)78257826def wait_distance_to_home(self, distance_min, distance_max, timeout=10, use_cached_home=True, **kwargs):7827"""Wait for distance to home to be within specified bounds."""7828assert distance_min <= distance_max, "Distance min should be less than distance max."78297830def get_distance():7831return self.distance_to_home(use_cached_home)78327833def validator(value2, target2=None):7834return distance_min <= value2 <= distance_max78357836self.wait_and_maintain(7837value_name="Distance to home",7838target=distance_min,7839current_value_getter=lambda: get_distance(),7840validator=lambda value2, target2: validator(value2, target2),7841accuracy=(distance_max - distance_min), timeout=timeout,7842**kwargs7843)78447845def assert_at_home(self, accuracy=1):7846if self.distance_to_home() > accuracy:7847raise NotAchievedException("Not at home")78487849def wait_distance_to_nav_target(self,7850distance_min,7851distance_max,7852timeout=10,7853use_cached_nav_controller_output=False,7854**kwargs):7855"""Wait for distance to home to be within specified bounds."""7856assert distance_min <= distance_max, "Distance min should be less than distance max."78577858def get_distance():7859return self.distance_to_nav_target(use_cached_nav_controller_output)78607861def validator(value2, target2=None):7862return distance_min <= value2 <= distance_max78637864self.wait_and_maintain(7865value_name="Distance to nav target",7866target=distance_min,7867current_value_getter=lambda: get_distance(),7868validator=lambda value2,7869target2: validator(value2, target2),7870accuracy=(distance_max - distance_min),7871timeout=timeout,7872**kwargs7873)78747875def distance_to_local_position(self, local_pos, timeout=30):7876(x, y, z_down) = local_pos # alt is *up*78777878pos = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)78797880delta_x = pos.x - x7881delta_y = pos.y - y7882delta_z = pos.z - z_down7883return math.sqrt(delta_x*delta_x + delta_y*delta_y + delta_z*delta_z)78847885def wait_distance_to_local_position(self,7886local_position, # (x, y, z_down)7887distance_min,7888distance_max,7889timeout=10,7890**kwargs):7891"""Wait for distance to home to be within specified bounds."""7892assert distance_min <= distance_max, "Distance min should be less than distance max."78937894def get_distance():7895return self.distance_to_local_position(local_position)78967897def validator(value2, target2=None):7898return distance_min <= value2 <= distance_max78997900(x, y, z_down) = local_position7901self.wait_and_maintain(7902value_name="Distance to (%f,%f,%f)" % (x, y, z_down),7903target=distance_min,7904current_value_getter=lambda: get_distance(),7905validator=lambda value2,7906target2: validator(value2, target2),7907accuracy=(distance_max - distance_min),7908timeout=timeout,7909**kwargs7910)79117912def wait_parameter_value(self, parameter, value, timeout=10):7913tstart = self.get_sim_time()7914while True:7915if self.get_sim_time_cached() - tstart > timeout:7916raise NotAchievedException("%s never got value %f" %7917(parameter, value))7918v = self.get_parameter(parameter, verbose=False)7919self.progress("Got parameter value (%s=%f)" %7920(parameter, v))7921if v == value:7922return7923self.delay_sim_time(0.1)79247925def get_servo_channel_value(self, channel, timeout=2):7926channel_field = "servo%u_raw" % channel7927tstart = self.get_sim_time()7928while True:7929remaining = timeout - (self.get_sim_time_cached() - tstart)7930if remaining <= 0:7931raise NotAchievedException("Channel value condition not met")7932m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',7933blocking=True,7934timeout=remaining)7935if m is None:7936continue7937m_value = getattr(m, channel_field, None)7938if m_value is None:7939raise ValueError("message (%s) has no field %s" %7940(str(m), channel_field))7941return m_value79427943def wait_servo_channel_value(self, channel, value, epsilon=0, timeout=2, comparator=operator.eq):7944"""wait for channel value comparison (default condition is equality)"""7945channel_field = "servo%u_raw" % channel7946opstring = ("%s" % comparator)[-3:-1]7947tstart = self.get_sim_time()7948while True:7949remaining = timeout - (self.get_sim_time_cached() - tstart)7950if remaining <= 0:7951raise NotAchievedException("Channel value condition not met")7952m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',7953blocking=True,7954timeout=remaining)7955if m is None:7956continue7957m_value = getattr(m, channel_field, None)7958if m_value is None:7959raise ValueError("message (%s) has no field %s" %7960(str(m), channel_field))7961self.progress("SERVO_OUTPUT_RAW.%s got=%u %s want=%u" %7962(channel_field, m_value, opstring, value))7963if comparator == operator.eq:7964if abs(m_value - value) <= epsilon:7965return m_value7966if comparator(m_value, value):7967return m_value79687969def wait_servo_channel_in_range(self, channel, v_min, v_max, timeout=2):7970"""wait for channel value to be within acceptable range"""7971channel_field = "servo%u_raw" % channel7972tstart = self.get_sim_time()7973while True:7974remaining = timeout - (self.get_sim_time_cached() - tstart)7975if remaining <= 0:7976raise NotAchievedException("Channel value condition not met")7977m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',7978blocking=True,7979timeout=remaining)7980if m is None:7981continue7982m_value = getattr(m, channel_field, None)7983if m_value is None:7984raise ValueError("message (%s) has no field %s" %7985(str(m), channel_field))7986self.progress("want %u <= SERVO_OUTPUT_RAW.%s <= %u, got value = %u" %7987(v_min, channel_field, v_max, m_value))7988if (v_min <= m_value) and (m_value <= v_max):7989return m_value79907991def assert_servo_channel_value(self, channel, value, comparator=operator.eq):7992"""assert channel value (default condition is equality)"""7993channel_field = "servo%u_raw" % channel7994opstring = ("%s" % comparator)[-3:-1]7995m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)7996m_value = getattr(m, channel_field, None)7997if m_value is None:7998raise ValueError("message (%s) has no field %s" %7999(str(m), channel_field))8000self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" %8001(channel_field, m_value, opstring, value))8002if comparator(m_value, value):8003return m_value8004raise NotAchievedException("Wrong value")80058006def assert_servo_channel_range(self, channel, value_min, value_max):8007"""assert channel value is within the range [value_min, value_max]"""8008channel_field = "servo%u_raw" % channel8009m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)8010m_value = getattr(m, channel_field, None)8011if m_value is None:8012raise ValueError("message (%s) has no field %s" %8013(str(m), channel_field))8014self.progress("assert SERVO_OUTPUT_RAW.%s=%u in [%u, %u]" %8015(channel_field, m_value, value_min, value_max))8016if m_value >= value_min and m_value <= value_max:8017return m_value8018raise NotAchievedException("Wrong value")80198020def get_rc_channel_value(self, channel, timeout=2):8021"""wait for channel to hit value"""8022channel_field = "chan%u_raw" % channel8023tstart = self.get_sim_time()8024while True:8025remaining = timeout - (self.get_sim_time_cached() - tstart)8026if remaining <= 0:8027raise NotAchievedException("Channel never achieved value")8028m = self.mav.recv_match(type='RC_CHANNELS',8029blocking=True,8030timeout=remaining)8031if m is None:8032continue8033m_value = getattr(m, channel_field)8034if m_value is None:8035raise ValueError("message (%s) has no field %s" %8036(str(m), channel_field))8037return m_value80388039def wait_rc_channel_value(self, channel, value, timeout=2):8040channel_field = "chan%u_raw" % channel8041tstart = self.get_sim_time()8042while True:8043remaining = timeout - (self.get_sim_time_cached() - tstart)8044if remaining <= 0:8045raise NotAchievedException("Channel never achieved value")8046m_value = self.get_rc_channel_value(channel, timeout=timeout)8047self.progress("RC_CHANNELS.%s=%u want=%u" %8048(channel_field, m_value, value))8049if value == m_value:8050return80518052def assert_rc_channel_value(self, channel, value):8053channel_field = "chan%u_raw" % channel80548055m_value = self.get_rc_channel_value(channel, timeout=1)8056self.progress("RC_CHANNELS.%s=%u want=%u" %8057(channel_field, m_value, value))8058if value != m_value:8059raise NotAchievedException("Expected %s to be %u got %u" %8060(channel, value, m_value))80618062def send_do_reposition(self,8063loc,8064frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT):8065'''send a DO_REPOSITION command for a location'''8066self.run_cmd_int(8067mavutil.mavlink.MAV_CMD_DO_REPOSITION,80680,80690,80700,80710,8072int(loc.lat*1e7), # lat* 1e78073int(loc.lng*1e7), # lon* 1e78074loc.alt,8075frame=frame8076)80778078def add_rally_point(self, loc, seq, total):8079'''add a rally point at the given location'''8080self.mav.mav.rally_point_send(1, # target system80810, # target component8082seq, # sequence number8083total, # total count8084int(loc.lat * 1e7),8085int(loc.lng * 1e7),8086loc.alt, # relative alt80870, # "break" alt?!80880, # "land dir"80890) # flags80908091def wait_location(self, loc, **kwargs):8092waiter = WaitAndMaintainLocation(self, loc, **kwargs)8093waiter.run()80948095def assert_current_waypoint(self, wpnum):8096seq = self.mav.waypoint_current()8097if seq != wpnum:8098raise NotAchievedException("Incorrect current wp")80998100def wait_current_waypoint(self, wpnum, timeout=70):8101tstart = self.get_sim_time()8102while True:8103if self.get_sim_time() - tstart > timeout:8104raise AutoTestTimeoutException("Did not get wanted current waypoint")8105seq = self.mav.waypoint_current()8106wp_dist = None8107try:8108wp_dist = self.mav.messages['NAV_CONTROLLER_OUTPUT'].wp_dist8109except (KeyError, AttributeError):8110pass8111self.progress("Waiting for wp=%u current=%u dist=%sm" % (wpnum, seq, wp_dist))8112if seq == wpnum:8113break81148115def wait_waypoint(self,8116wpnum_start,8117wpnum_end,8118allow_skip=True,8119max_dist=2,8120timeout=400,8121ignore_RTL_mode_change=False):8122"""Wait for waypoint ranges."""8123tstart = self.get_sim_time()8124# this message arrives after we set the current WP8125start_wp = self.mav.waypoint_current()8126current_wp = start_wp8127mode = self.mav.flightmode81288129self.progress("wait for waypoint ranges start=%u end=%u"8130% (wpnum_start, wpnum_end))8131# if start_wp != wpnum_start:8132# raise WaitWaypointTimeout("test: Expected start waypoint %u "8133# "but got %u" %8134# (wpnum_start, start_wp))81358136last_wp_msg = 08137while self.get_sim_time_cached() < tstart + timeout:8138seq = self.mav.waypoint_current()8139m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT')8140wp_dist = m.wp_dist8141m = self.assert_receive_message('VFR_HUD')81428143# if we changed mode, fail8144if not self.mode_is('AUTO'):8145self.progress(f"{self.mav.flightmode} vs {self.get_mode_from_mode_mapping(mode)}")8146if not ignore_RTL_mode_change or not self.mode_is('RTL', cached=True):8147new_mode_str = self.get_mode_string_for_mode(self.get_mode())8148raise WaitWaypointTimeout(f'Exited {mode} mode to {new_mode_str} ignore={ignore_RTL_mode_change}')81498150if self.get_sim_time_cached() - last_wp_msg > 1:8151self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u,"8152"wpnum_end: %u" %8153(seq, wp_dist, m.alt, current_wp, wpnum_end))8154last_wp_msg = self.get_sim_time_cached()8155if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):8156self.progress("WW: Starting new waypoint %u" % seq)8157tstart = self.get_sim_time()8158current_wp = seq8159# the wp_dist check is a hack until we can sort out8160# the right seqnum for end of mission8161# if current_wp == wpnum_end or (current_wp == wpnum_end-1 and8162# wp_dist < 2):8163if current_wp == wpnum_end and wp_dist < max_dist:8164self.progress("Reached final waypoint %u" % seq)8165return True8166if seq >= 255:8167self.progress("Reached final waypoint %u" % seq)8168return True8169if seq > current_wp+1:8170raise WaitWaypointTimeout(("Skipped waypoint! Got wp %u expected %u"8171% (seq, current_wp+1)))8172raise WaitWaypointTimeout("Timed out waiting for waypoint %u of %u" %8173(wpnum_end, wpnum_end))81748175def get_cached_message(self, message_type):8176'''returns the most-recently received instance of message_type'''8177return self.mav.messages[message_type]81788179def mode_is(self, mode, cached=False, drain_mav=True, drain_mav_quietly=True):8180if not cached:8181self.wait_heartbeat(drain_mav=drain_mav, quiet=drain_mav_quietly)8182try:8183return self.get_mode_from_mode_mapping(self.mav.flightmode) == self.get_mode_from_mode_mapping(mode)8184except Exception:8185pass8186# assume this is a number....8187return self.mav.messages['HEARTBEAT'].custom_mode == mode81888189def wait_mode(self, mode, timeout=60):8190"""Wait for mode to change."""8191self.progress("Waiting for mode %s" % mode)8192tstart = self.get_sim_time()8193while not self.mode_is(mode, drain_mav=False):8194custom_num = self.mav.messages['HEARTBEAT'].custom_mode8195self.progress("mav.flightmode=%s Want=%s custom=%u" % (8196self.mav.flightmode, mode, custom_num))8197if (timeout is not None and8198self.get_sim_time_cached() > tstart + timeout):8199raise WaitModeTimeout("Did not change mode")8200self.progress("Got mode %s" % mode)82018202def assert_mode_is(self, mode):8203if not self.mode_is(mode):8204raise NotAchievedException("Expected mode %s" % str(mode))82058206def get_mode(self, cached=False, drain_mav=True):8207'''return numeric custom mode'''8208if not cached:8209self.wait_heartbeat(drain_mav=drain_mav)8210return self.mav.messages['HEARTBEAT'].custom_mode82118212def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30):8213self.progress("Waiting for GPS health")8214tstart = self.get_sim_time()8215while True:8216now = self.get_sim_time_cached()8217if now - tstart > timeout:8218raise AutoTestTimeoutException("GPS status bits did not become good")8219m = self.mav.recv_match(type='SYS_STATUS', blocking=True, timeout=1)8220if m is None:8221continue8222if (not (m.onboard_control_sensors_present & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8223self.progress("GPS not present")8224if now > 20:8225# it's had long enough to be detected....8226return8227continue8228if (not (m.onboard_control_sensors_enabled & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8229self.progress("GPS not enabled")8230continue8231if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8232self.progress("GPS not healthy")8233continue8234self.progress("GPS healthy after %f/%f seconds" %8235((now - tstart), timeout))8236return82378238def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False):8239return self.sensor_has_state(sensor, present, enabled, healthy, do_assert=True, verbose=verbose)82408241def sensor_has_state(self, sensor, present=True, enabled=True, healthy=True, do_assert=False, verbose=False):8242m = self.assert_receive_message('SYS_STATUS', timeout=5, very_verbose=verbose)8243reported_present = m.onboard_control_sensors_present & sensor8244reported_enabled = m.onboard_control_sensors_enabled & sensor8245reported_healthy = m.onboard_control_sensors_health & sensor8246if present:8247if not reported_present:8248if do_assert:8249raise NotAchievedException("Sensor not present")8250return False8251else:8252if reported_present:8253if do_assert:8254raise NotAchievedException("Sensor present when it shouldn't be")8255return False82568257if enabled:8258if not reported_enabled:8259if do_assert:8260raise NotAchievedException("Sensor not enabled")8261return False8262else:8263if reported_enabled:8264if do_assert:8265raise NotAchievedException("Sensor enabled when it shouldn't be")8266return False82678268if healthy:8269if not reported_healthy:8270if do_assert:8271raise NotAchievedException("Sensor not healthy")8272return False8273else:8274if reported_healthy:8275if do_assert:8276raise NotAchievedException("Sensor healthy when it shouldn't be")8277return False8278return True82798280def wait_sensor_state(self, sensor, present=True, enabled=True, healthy=True, timeout=5, verbose=False):8281tstart = self.get_sim_time()8282while True:8283if self.get_sim_time_cached() - tstart > timeout:8284raise NotAchievedException("Sensor did not achieve state")8285if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose):8286break82878288def wait_not_ready_to_arm(self):8289self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False)82908291def wait_prearm_sys_status_healthy(self, timeout=60):8292self.do_timesync_roundtrip()8293tstart = self.get_sim_time()8294while True:8295t2 = self.get_sim_time_cached()8296if t2 - tstart > timeout:8297self.progress("Prearm bit never went true. Attempting arm to elicit reason from autopilot")8298try:8299self.arm_vehicle()8300except Exception:8301pass8302raise AutoTestTimeoutException("Prearm bit never went true")8303if self.sensor_has_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, True):8304break83058306def assert_fence_enabled(self, timeout=2):8307# Check fence is enabled8308m = self.assert_receive_message('FENCE_STATUS', timeout=timeout)8309self.progress("Got (%s)" % str(m))83108311def assert_fence_disabled(self, timeout=2):8312# Check fence is not enabled8313self.assert_not_receiving_message('FENCE_STATUS', timeout=timeout)83148315def NoArmWithoutMissionItems(self):8316'''ensure we can't arm in auto mode without mission items present'''8317# load a trivial mission8318items = []8319items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 20000),)8320items.append((mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0))8321self.upload_simple_relhome_mission(items)83228323self.change_mode('AUTO')8324self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)8325self.assert_prearm_failure('Mode requires mission',8326other_prearm_failures_fatal=False)83278328def assert_prearm_failure(self,8329expected_statustext,8330timeout=5,8331ignore_prearm_failures=[],8332other_prearm_failures_fatal=True):8333seen_statustext = False8334seen_command_ack = False83358336self.drain_mav()8337tstart = self.get_sim_time_cached()8338arm_last_send = 08339while True:8340if seen_command_ack and seen_statustext:8341break8342now = self.get_sim_time_cached()8343if now - tstart > timeout:8344raise NotAchievedException(8345"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %8346(seen_statustext, seen_command_ack))8347if now - arm_last_send > 1:8348arm_last_send = now8349self.send_mavlink_run_prearms_command()8350m = self.mav.recv_match(blocking=True, timeout=1)8351if m is None:8352continue8353if m.get_type() == "STATUSTEXT":8354if expected_statustext in m.text:8355self.progress("Got: %s" % str(m))8356seen_statustext = True8357elif other_prearm_failures_fatal and "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:8358self.progress("Got: %s" % str(m))8359raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)83608361if m.get_type() == "COMMAND_ACK":8362print("Got: %s" % str(m))8363if m.command == mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS:8364if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:8365raise NotAchievedException("command-ack says we didn't run prearms")8366self.progress("Got: %s" % str(m))8367seen_command_ack = True8368if self.mav.motors_armed():8369raise NotAchievedException("Armed when we shouldn't have")83708371def assert_arm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]):8372seen_statustext = False8373seen_command_ack = False83748375self.drain_mav()8376tstart = self.get_sim_time_cached()8377arm_last_send = 08378while True:8379if seen_command_ack and seen_statustext:8380break8381now = self.get_sim_time_cached()8382if now - tstart > timeout:8383raise NotAchievedException(8384"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %8385(seen_statustext, seen_command_ack))8386if now - arm_last_send > 1:8387arm_last_send = now8388self.send_mavlink_arm_command()8389m = self.mav.recv_match(blocking=True, timeout=1)8390if m is None:8391continue8392if m.get_type() == "STATUSTEXT":8393if expected_statustext in m.text:8394self.progress("Got: %s" % str(m))8395seen_statustext = True8396elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:8397self.progress("Got: %s" % str(m))8398raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)83998400if m.get_type() == "COMMAND_ACK":8401print("Got: %s" % str(m))8402if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:8403if m.result != 4:8404raise NotAchievedException("command-ack says we didn't fail to arm")8405self.progress("Got: %s" % str(m))8406seen_command_ack = True8407if self.mav.motors_armed():8408raise NotAchievedException("Armed when we shouldn't have")84098410def wait_ready_to_arm(self, timeout=120, require_absolute=True, check_prearm_bit=True):8411# wait for EKF checks to pass8412self.progress("Waiting for ready to arm")8413start = self.get_sim_time()8414self.wait_ekf_happy(timeout=timeout, require_absolute=require_absolute)8415if require_absolute:8416self.wait_gps_sys_status_not_present_or_enabled_and_healthy()8417if require_absolute:8418self.poll_home_position()8419if check_prearm_bit:8420self.wait_prearm_sys_status_healthy(timeout=timeout)8421armable_time = self.get_sim_time() - start8422self.progress("Took %u seconds to become armable" % armable_time)8423self.total_waiting_to_arm_time += armable_time8424self.waiting_to_arm_count += 184258426def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x):8427'''as opposed to mav.wait_heartbeat, raises an exception on timeout.8428Also, ignores heartbeats not from our target system'''8429if drain_mav:8430self.drain_mav(quiet=quiet)8431orig_timeout = x.get("timeout", 20)8432x["timeout"] = 18433tstart = time.time()8434while True:8435if time.time() - tstart > orig_timeout and not self.gdb:8436if not self.sitl_is_running():8437self.progress("SITL is not running")8438raise AutoTestTimeoutException("Did not receive heartbeat")8439m = self.mav.wait_heartbeat(*args, **x)8440if m is None:8441continue8442if m.get_srcSystem() == self.sysid_thismav():8443return m84448445def wait_ekf_happy(self, require_absolute=True, **kwargs):8446"""Wait for EKF to be happy"""8447if "timeout" not in kwargs:8448kwargs["timeout"] = 4584498450""" if using SITL estimates directly """8451if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):8452return True84538454# all of these must be set for arming to happen:8455required_value = (mavutil.mavlink.EKF_ATTITUDE |8456mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ |8457mavutil.mavlink.ESTIMATOR_VELOCITY_VERT |8458mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL |8459mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_REL)8460# none of these bits must be set for arming to happen:8461error_bits = (mavutil.mavlink.ESTIMATOR_CONST_POS_MODE |8462mavutil.mavlink.ESTIMATOR_ACCEL_ERROR)8463if require_absolute:8464required_value |= (mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS |8465mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |8466mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)8467error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH8468WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()84698470def wait_ekf_flags(self, required_value, error_bits, **kwargs):8471WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()84728473def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):8474"""Disable GPS and wait for EKF to report the end of assistance from GPS."""8475self.set_parameter("SIM_GPS1_ENABLE", 0)8476tstart = self.get_sim_time()84778478""" if using SITL estimates directly """8479if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):8480self.progress("GPS disable skipped")8481return84828483# all of these must NOT be set for arming NOT to happen:8484not_required_value = 08485if position_horizontal:8486not_required_value |= mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL8487if position_vertical:8488not_required_value |= mavutil.mavlink.ESTIMATOR_POS_VERT_AGL8489self.progress("Waiting for EKF not having bits %u" % not_required_value)8490last_print_time = 08491while timeout is None or self.get_sim_time_cached() < tstart + timeout:8492esr = self.assert_receive_message('EKF_STATUS_REPORT', timeout=timeout)8493current = esr.flags8494if self.get_sim_time_cached() - last_print_time > 1:8495self.progress("Wait EKF.flags: not required:%u current:%u" %8496(not_required_value, current))8497last_print_time = self.get_sim_time_cached()8498if current & not_required_value != not_required_value:8499self.progress("GPS disable OK")8500return8501self.progress(f"Last EKF_STATUS_REPORT: {esr}")8502raise AutoTestTimeoutException("Failed to get EKF.flags=%u disabled" % not_required_value)85038504def wait_text(self, *args, **kwargs):8505'''wait for text to appear from vehicle, return that text'''8506statustext = self.wait_statustext(*args, **kwargs)8507if statustext is None:8508return None8509return statustext.text85108511def statustext_in_collections(self, text, regex=False):8512'''searches for text in STATUSTEXT collection, returns message if found'''8513c = self.context_get()8514if "STATUSTEXT" not in c.collections:8515raise NotAchievedException("Asked to check context but it isn't collecting!")8516for x in c.collections["STATUSTEXT"]:8517self.progress(" statustext got=(%s) want=(%s)" % (x.text, text))8518if regex:8519if re.match(text, x.text):8520return x8521elif text.lower() in x.text.lower():8522return x8523return None85248525def wait_statustext(self, text, timeout=20, the_function=None, check_context=False, regex=False, wallclock_timeout=False):8526"""Wait for a specific STATUSTEXT, return that statustext message"""85278528# Statustexts are often triggered by something we've just8529# done, so we have to be careful not to read any traffic that8530# isn't checked for being our statustext. That doesn't work8531# well with getting the curent simulation time (which requires8532# a new SYSTEM_TIME message), so we install a message hook8533# which checks all incoming messages.8534self.progress("Waiting for text : %s" % text.lower())8535if check_context:8536statustext = self.statustext_in_collections(text, regex=regex)8537if statustext:8538self.progress("Found expected text in collection: %s" % text.lower())8539return statustext85408541global statustext_found8542global statustext_full8543statustext_full = None8544statustext_found = False85458546def mh(mav, m):8547global statustext_found8548global statustext_full8549if m.get_type() != "STATUSTEXT":8550return8551if regex:8552self.re_match = re.match(text, m.text)8553if self.re_match:8554statustext_found = True8555statustext_full = m8556if text.lower() in m.text.lower():8557self.progress("Received expected text: %s" % m.text.lower())8558statustext_found = True8559statustext_full = m85608561self.install_message_hook(mh)8562if wallclock_timeout:8563tstart = time.time()8564else:8565tstart = self.get_sim_time()8566try:8567while not statustext_found:8568if wallclock_timeout:8569now = time.time()8570else:8571now = self.get_sim_time_cached()8572if now - tstart > timeout:8573raise AutoTestTimeoutException("Failed to receive text: %s" %8574text.lower())8575if the_function is not None:8576the_function()8577self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)8578finally:8579self.remove_message_hook(mh)8580return statustext_full85818582# routines helpful for testing LUA scripting:8583def script_example_source_path(self, scriptname):8584return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "examples", scriptname)85858586def script_test_source_path(self, scriptname):8587return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", scriptname)85888589def script_applet_source_path(self, scriptname):8590return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "applets", scriptname)85918592def installed_script_path(self, scriptname):8593return os.path.join("scripts", os.path.basename(scriptname))85948595def install_script(self, source, scriptname, install_name=None):8596if install_name is not None:8597dest = self.installed_script_path(install_name)8598else:8599dest = self.installed_script_path(scriptname)86008601destdir = os.path.dirname(dest)8602if not os.path.exists(destdir):8603os.mkdir(destdir)8604self.progress("Copying (%s) to (%s)" % (source, dest))8605shutil.copy(source, dest)86068607def installed_script_module_path(self, modulename):8608return os.path.join("scripts", "modules", os.path.basename(modulename))86098610def install_script_module(self, source, modulename, install_name=None):8611if install_name is not None:8612dest = self.installed_script_module_path(install_name)8613else:8614dest = self.installed_script_module_path(modulename)86158616destdir = os.path.dirname(dest)8617os.makedirs(destdir, exist_ok=True)8618self.progress("Copying (%s) to (%s)" % (source, dest))8619shutil.copy(source, dest)86208621def install_test_modules(self):8622source = os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", "modules", "test")8623dest = os.path.join("scripts", "modules", "test")8624self.progress("Copying (%s) to (%s)" % (source, dest))8625shutil.copytree(source, dest)86268627def install_mavlink_module(self):8628dest = os.path.join("scripts", "modules", "mavlink")8629ardupilotmega_xml = os.path.join(self.rootdir(), "modules", "mavlink",8630"message_definitions", "v1.0", "ardupilotmega.xml")8631mavgen.mavgen(mavgen.Opts(output=dest, wire_protocol='2.0', language='Lua'), [ardupilotmega_xml])8632self.progress("Installed mavlink module")86338634def install_example_script(self, scriptname):8635source = self.script_example_source_path(scriptname)8636self.install_script(source, scriptname)86378638def install_test_script(self, scriptname):8639source = self.script_test_source_path(scriptname)8640self.install_script(source, scriptname)86418642def install_applet_script(self, scriptname, install_name=None):8643source = self.script_applet_source_path(scriptname)8644self.install_script(source, scriptname, install_name=install_name)86458646def remove_installed_script(self, scriptname):8647dest = self.installed_script_path(os.path.basename(scriptname))8648try:8649os.unlink(dest)8650except IOError:8651pass8652except OSError:8653pass86548655def remove_installed_script_module(self, modulename):8656path = self.installed_script_module_path(modulename)8657os.unlink(path)86588659def remove_installed_modules(self, modulename):8660dest = os.path.join("scripts", "modules", modulename)8661try:8662shutil.rmtree(dest)8663except IOError:8664pass8665except OSError:8666pass86678668def get_mavlink_connection_going(self):8669# get a mavlink connection going8670try:8671retries = 208672if self.gdb:8673retries = 200008674self.mav = mavutil.mavlink_connection(8675self.autotest_connection_string_to_ardupilot(),8676retries=retries,8677robust_parsing=True,8678source_system=250,8679source_component=250,8680autoreconnect=True,8681dialect="all", # if we don't pass this in we end up with the wrong mavlink version...8682)8683except Exception as msg:8684self.progress("Failed to start mavlink connection on %s: %s" %8685(self.autotest_connection_string_to_ardupilot(), msg,))8686raise8687self.mav.message_hooks.append(self.message_hook)8688self.mav.mav.set_send_callback(self.send_message_hook, self)8689self.mav.idle_hooks.append(self.idle_hook)86908691# we need to wait for a heartbeat here. If we don't then8692# self.mav.target_system will be zero because it hasn't8693# "locked on" to a target system yet.8694self.wait_heartbeat()8695self.set_streamrate(self.sitl_streamrate())86968697def show_test_timings_key_sorter(self, t):8698(k, v) = t8699return ((v, k))87008701def show_test_timings(self):8702if len(self.test_timings.keys()) == 0:8703return8704longest = 08705for desc in self.test_timings.keys():8706if len(desc) > longest:8707longest = len(desc)8708tests_total_time = 08709for desc, test_time in sorted(self.test_timings.items(),8710key=self.show_test_timings_key_sorter):8711fmt = "%" + str(longest) + "s: %.2fs"8712tests_total_time += test_time8713self.progress(fmt % (desc, test_time))8714self.progress(fmt % ("**--tests_total_time--**", tests_total_time))8715self.progress("mavproxy_start was called %u times" %8716(self.start_mavproxy_count,))8717self.progress("Supplied terrain data to autopilot in %u messages" %8718(self.terrain_data_messages_sent,))87198720def send_statustext(self, text):8721if sys.version_info.major >= 3 and not isinstance(text, bytes):8722text = bytes(text, "ascii")8723elif 'unicode' in str(type(text)):8724text = text.encode('ascii')8725seq = 08726while len(text):8727self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text[:50], id=self.statustext_id, chunk_seq=seq)8728text = text[50:]8729seq += 18730self.statustext_id += 18731if self.statustext_id > 255:8732self.statustext_id = 187338734def get_stacktrace(self):8735return ''.join(traceback.format_stack())87368737def get_exception_stacktrace(self, e):8738if sys.version_info[0] >= 3:8739ret = "%s\n" % e8740ret += ''.join(traceback.format_exception(type(e),8741e,8742tb=e.__traceback__))8743return ret87448745# Python2:8746return traceback.format_exc(e)87478748def bin_logs(self):8749return glob.glob("logs/*.BIN")87508751def remove_bin_logs(self):8752util.run_cmd('/bin/rm -f logs/*.BIN logs/LASTLOG.TXT')87538754def remove_ardupilot_terrain_cache(self):8755'''removes the terrain files ArduPilot keeps in its onboiard storage'''8756util.run_cmd('/bin/rm -f %s' % util.reltopdir("terrain/*.DAT"))87578758def check_logs(self, name):8759'''called to move relevant log files from our working directory to the8760buildlogs directory'''8761to_dir = self.logs_dir8762# move telemetry log files8763for log in glob.glob("autotest-*.tlog"):8764bname = os.path.basename(log)8765newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))8766print("Renaming %s to %s" % (log, newname))8767shutil.move(log, newname)8768# move binary log files8769for log in sorted(self.bin_logs()):8770bname = os.path.basename(log)8771newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))8772print("Renaming %s to %s" % (log, newname))8773shutil.move(log, newname)8774# move core files8775save_binaries = False8776corefiles = []8777corefiles.extend(glob.glob("core*"))8778corefiles.extend(glob.glob("ap-*.core"))8779for log in sorted(corefiles):8780bname = os.path.basename(log)8781newname = os.path.join(to_dir, "%s-%s-%s" % (bname, self.log_name(), name))8782print("Renaming %s to %s" % (log, newname))8783shutil.move(log, newname)8784save_binaries = True8785if save_binaries:8786util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir,8787directory=util.reltopdir('.'))87888789def run_one_test(self, test, interact=False, suppress_stdout=False):8790'''new-style run-one-test used by run_tests'''8791for i in range(0, test.attempts-1):8792result = self.run_one_test_attempt(test, interact=interact, attempt=i+2, suppress_stdout=suppress_stdout)8793if result.passed:8794return result8795self.progress("Run attempt failed. Retrying")8796return self.run_one_test_attempt(test, interact=interact, attempt=1, suppress_stdout=suppress_stdout)87978798def print_exception_caught(self, e, send_statustext=True):8799self.progress("Exception caught: %s" %8800self.get_exception_stacktrace(e))8801path = None8802try:8803path = self.current_onboard_log_filepath()8804except IndexError:8805pass8806self.progress("Most recent logfile: %s" % (path, ), send_statustext=send_statustext)88078808def progress_file_content(self, filepath):8809with open(filepath) as f:8810for line in f:8811self.progress(line.rstrip())88128813def dump_process_status(self, result):8814'''used to show where the SITL process is upto. Often caused when8815we've lost contact'''88168817if self.sitl.isalive():8818self.progress("pexpect says it is alive")8819for tool in "dumpstack.sh", "dumpcore.sh":8820tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)8821if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:8822reason = "Failed %s" % (tool,)8823self.progress(reason)8824result.reason = reason8825result.passed = False8826else:8827self.progress("pexpect says it is dead")88288829# try dumping the process status file for more information:8830status_filepath = "/proc/%u/status" % self.sitl.pid8831self.progress("Checking for status filepath (%s)" % status_filepath)8832if os.path.exists(status_filepath):8833self.progress_file_content(status_filepath)8834else:8835self.progress("... does not exist")88368837def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=False):8838'''called by run_one_test to actually run the test in a retry loop'''8839name = test.name8840desc = test.description8841test_function = test.function8842test_kwargs = test.kwargs8843if attempt != 1:8844self.progress("RETRYING %s" % name)8845test_output_filename = self.buildlogs_path("%s-%s-retry-%u.txt" %8846(self.log_name(), name, attempt-1))8847else:8848test_output_filename = self.buildlogs_path("%s-%s.txt" %8849(self.log_name(), name))88508851tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)88528853start_message_hooks = copy.copy(self.message_hooks)88548855prettyname = "%s (%s)" % (name, desc)8856self.start_test(prettyname)8857self.set_current_test_name(name)8858old_contexts_length = len(self.contexts)8859self.context_push()88608861start_time = time.time()88628863orig_speedup = None88648865hooks_removed = False88668867ex = None8868try:8869self.check_rc_defaults()8870self.change_mode(self.default_mode())8871# ArduPilot can still move the current waypoint from 0,8872# even if we are not in AUTO mode, so cehck_afterwards=False:8873self.set_current_waypoint(0, check_afterwards=False)8874self.drain_mav()8875self.drain_all_pexpects()8876if test.speedup is not None:8877self.progress("Overriding speedup to %u" % test.speedup)8878orig_speedup = self.get_parameter("SIM_SPEEDUP")8879self.set_parameter("SIM_SPEEDUP", test.speedup)88808881test_function(**test_kwargs)8882except Exception as e:8883self.print_exception_caught(e)8884ex = e8885# reset the message hooks; we've failed-via-exception and8886# can't expect the hooks to have been cleaned up8887for h in copy.copy(self.message_hooks):8888if h not in start_message_hooks:8889self.message_hooks.remove(h)8890hooks_removed = True8891self.test_timings[desc] = time.time() - start_time8892reset_needed = self.contexts[-1].sitl_commandline_customised88938894if orig_speedup is not None:8895self.set_parameter("SIM_SPEEDUP", orig_speedup)88968897passed = True8898if ex is not None:8899passed = False89008901result = Result(test)8902result.time_elapsed = self.test_timings[desc]89038904ardupilot_alive = False8905try:8906self.wait_heartbeat()8907ardupilot_alive = True8908except Exception:8909# process is dead8910self.progress("No heartbeat after test", send_statustext=False)8911self.dump_process_status(result)89128913passed = False8914reset_needed = True89158916try:8917self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)8918except Exception as e:8919self.print_exception_caught(e, send_statustext=False)8920passed = False89218922# if we haven't already reset ArduPilot because it's dead,8923# then ensure the vehicle was disarmed at the end of the test.8924# If it wasn't then the test is considered failed:8925if ardupilot_alive and self.armed() and not self.is_tracker():8926if ex is None:8927ex = ArmedAtEndOfTestException("Still armed at end of test")8928self.progress("Armed at end of test; force-rebooting SITL")8929self.set_rc_default() # otherwise we might start calibrating ESCs...8930try:8931self.disarm_vehicle(force=True)8932except AutoTestTimeoutException:8933reset_needed = True8934self.forced_post_test_sitl_reboots += 18935if reset_needed:8936self.progress("Force-resetting SITL")8937self.reset_SITL_commandline()8938else:8939self.progress("Force-rebooting SITL")8940self.zero_throttle()8941self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it8942passed = False8943elif ardupilot_alive and not passed: # implicit reboot after a failed test:8944self.progress("Test failed but ArduPilot process alive; rebooting")8945self.reboot_sitl() # that'll learn it89468947if self._mavproxy is not None:8948self.progress("Stopping auto-started mavproxy")8949if self.use_map:8950self.mavproxy.send("module unload map\n")8951self.mavproxy.expect("Unloaded module map")89528953self.expect_list_remove(self._mavproxy)8954util.pexpect_close(self._mavproxy)8955self._mavproxy = None89568957corefiles = []8958corefiles.extend(glob.glob("core*"))8959corefiles.extend(glob.glob("ap-*.core"))8960if corefiles:8961self.progress('Corefiles detected: %s' % str(corefiles))8962passed = False89638964if len(self.contexts) != old_contexts_length:8965self.progress("context count mismatch (want=%u got=%u); popping extras" %8966(old_contexts_length, len(self.contexts)))8967passed = False8968# pop off old contexts to clean up message hooks etc8969while len(self.contexts) > old_contexts_length:8970try:8971self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)8972except Exception as e:8973self.print_exception_caught(e, send_statustext=False)8974self.progress("Done popping extra contexts")89758976# make sure we don't leave around stray listeners:8977if len(self.message_hooks) != len(start_message_hooks):8978self.progress("Stray message listeners: %s vs start %s" %8979(str(self.message_hooks), str(start_message_hooks)))8980passed = False89818982if passed:8983# self.remove_bin_logs() # can't do this as one of the binlogs is probably open for writing by the SITL process. If we force a rotate before running tests then we can do this. # noqa8984pass8985else:8986if self.logs_dir is not None:8987# stash the binary logs and corefiles away for later analysis8988self.check_logs(name)89898990if passed:8991self.progress('PASSED: "%s"' % prettyname)8992else:8993self.progress('FAILED: "%s": %s (see %s)' %8994(prettyname, repr(ex), test_output_filename))8995result.exception = ex8996result.debug_filename = test_output_filename8997if interact:8998self.progress("Starting MAVProxy interaction as directed")8999self.mavproxy.interact()90009001if self.reset_after_every_test:9002reset_needed = True90039004if reset_needed:9005self.reset_SITL_commandline()90069007if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling9008self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)9009self.set_current_waypoint(0, check_afterwards=False)90109011tee.close()90129013result.passed = passed9014return result90159016def defaults_filepath(self):9017return None90189019def start_mavproxy(self, sitl_rcin_port=None, master=None, options=None):9020self.start_mavproxy_count += 19021if self.mavproxy is not None:9022return self.mavproxy9023self.progress("Starting MAVProxy")90249025# determine a good pexpect timeout for reading MAVProxy's9026# output; some regmes may require longer timeouts.9027pexpect_timeout = 609028if self.valgrind or self.callgrind:9029pexpect_timeout *= 1090309031if sitl_rcin_port is None:9032sitl_rcin_port = self.sitl_rcin_port()90339034if master is None:9035master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762)90369037if options is None:9038options = self.mavproxy_options()9039else:9040op = self.mavproxy_options().copy()9041op.extend(options)9042options = op90439044mavproxy = util.start_MAVProxy_SITL(9045self.vehicleinfo_key(),9046master=master,9047logfile=self.mavproxy_logfile,9048options=options,9049pexpect_timeout=pexpect_timeout,9050sitl_rcin_port=sitl_rcin_port,9051)9052mavproxy.expect(r'Telemetry log: (\S+)\r\n')9053self.logfile = mavproxy.match.group(1)9054self.progress("LOGFILE %s" % self.logfile)9055self.try_symlink_tlog()90569057self.expect_list_add(mavproxy)9058util.expect_setup_callback(mavproxy, self.expect_callback)9059self._mavproxy = mavproxy # so we can clean up after tests....9060return mavproxy90619062def stop_mavproxy(self, mavproxy):9063if self.mavproxy is not None:9064return9065self.progress("Stopping MAVProxy")9066self.expect_list_remove(mavproxy)9067util.pexpect_close(mavproxy)9068self._mavproxy = None90699070def start_SITL(self, binary=None, sitl_home=None, **sitl_args):9071if sitl_home is None:9072sitl_home = self.sitl_home()9073start_sitl_args = {9074"breakpoints": self.breakpoints,9075"disable_breakpoints": self.disable_breakpoints,9076"gdb": self.gdb,9077"gdb_no_tui": self.gdb_no_tui,9078"gdbserver": self.gdbserver,9079"lldb": self.lldb,9080"home": sitl_home,9081"speedup": self.speedup,9082"valgrind": self.valgrind,9083"callgrind": self.callgrind,9084"wipe": True,9085"enable_fgview": self.enable_fgview,9086}9087start_sitl_args.update(**sitl_args)9088if ("defaults_filepath" not in start_sitl_args or9089start_sitl_args["defaults_filepath"] is None):9090start_sitl_args["defaults_filepath"] = self.defaults_filepath()90919092if "model" not in start_sitl_args or start_sitl_args["model"] is None:9093start_sitl_args["model"] = self.frame9094self.progress("Starting SITL", send_statustext=False)9095if binary is None:9096binary = self.binary9097self.sitl = util.start_SITL(binary, **start_sitl_args)9098self.expect_list_add(self.sitl)9099self.sup_prog = []9100count = 09101for sup_binary in self.sup_binaries:9102self.progress("Starting Supplementary Program ", sup_binary)9103start_sitl_args["customisations"] = [sup_binary['customisation']]9104start_sitl_args["supplementary"] = True9105start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count)9106start_sitl_args["defaults_filepath"] = sup_binary['param_file']9107sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)9108self.sup_prog.append(sup_prog_link)9109self.expect_list_add(sup_prog_link)9110count += 191119112# mavlink will have disconnected here. Explicitly reconnect,9113# or the first packet we send will be lost:9114if self.mav is not None:9115self.mav.reconnect()91169117def get_supplementary_programs(self):9118return self.sup_prog91199120def stop_sup_program(self, instance=None):9121self.progress("Stopping supplementary program")9122if instance is None:9123# close all sup programs9124for prog in self.sup_prog:9125self.expect_list_remove(prog)9126self.sup_prog.remove(prog)9127util.pexpect_close(prog)9128else:9129# close only the instance passed9130prog = self.sup_prog[instance]9131self.expect_list_remove(prog)9132self.sup_prog[instance] = None9133util.pexpect_close(prog)91349135def start_sup_program(self, instance=None, args=None):9136self.progress("Starting supplementary program")9137start_sitl_args = {9138"breakpoints": self.breakpoints,9139"disable_breakpoints": self.disable_breakpoints,9140"gdb": self.gdb,9141"gdb_no_tui": self.gdb_no_tui,9142"gdbserver": self.gdbserver,9143"lldb": self.lldb,9144"home": self.sitl_home(),9145"speedup": self.speedup,9146"valgrind": self.valgrind,9147"callgrind": self.callgrind,9148"wipe": True,9149}9150for i in range(len(self.sup_binaries)):9151if instance is not None and instance != i:9152continue9153sup_binary = self.sup_binaries[i]9154start_sitl_args["customisations"] = [sup_binary['customisation']]9155if args is not None:9156start_sitl_args["customisations"] = [sup_binary['customisation'], args]9157start_sitl_args["supplementary"] = True9158start_sitl_args["defaults_filepath"] = sup_binary['param_file']9159sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)9160time.sleep(1)9161self.sup_prog[i] = sup_prog_link # add to list9162self.expect_list_add(sup_prog_link) # add to expect list91639164def sitl_is_running(self):9165if self.sitl is None:9166return False9167return self.sitl.isalive()91689169def autostart_mavproxy(self):9170return self.use_map91719172def init(self):9173"""Initilialize autotest feature."""9174self.mavproxy_logfile = self.open_mavproxy_logfile()91759176if self.frame is None:9177self.frame = self.default_frame()91789179if self.frame is None:9180raise ValueError("frame must not be None")91819182self.progress("Starting simulator")9183self.start_SITL()91849185os.environ['MAVLINK20'] = '1'91869187self.progress("Starting MAVLink connection")9188self.get_mavlink_connection_going()91899190if self.autostart_mavproxy():9191self.mavproxy = self.start_mavproxy()91929193self.expect_list_clear()9194self.expect_list_extend([self.sitl, self.mavproxy])9195self.expect_list_extend(self.sup_prog)91969197# need to wait for a heartbeat to arrive as then mavutil will9198# select the correct set of messages for us to receive in9199# self.mav.messages. You can actually receive messages with9200# recv_match and those will not be in self.mav.messages until9201# you do this!9202self.wait_heartbeat()9203self.get_autopilot_firmware_version()9204self.progress("Sim time: %f" % (self.get_sim_time(),))9205self.apply_default_parameters()92069207if not self.sitl_is_running():9208# we run this just to make sure exceptions are likely to9209# work OK.9210raise NotAchievedException("SITL is not running")9211self.progress("SITL is running")92129213self.progress("Ready to start testing!")92149215def upload_using_mission_protocol(self, mission_type, items):9216'''mavlink2 required'''9217target_system = 19218target_component = 19219self.do_timesync_roundtrip()9220tstart = self.get_sim_time()9221self.mav.mav.mission_count_send(target_system,9222target_component,9223len(items),9224mission_type)9225remaining_to_send = set(range(0, len(items)))9226sent = set()9227timeout = (10 + len(items)/10.0)9228while True:9229if self.get_sim_time_cached() - tstart > timeout:9230raise NotAchievedException("timeout uploading %s" % str(mission_type))9231if len(remaining_to_send) == 0:9232self.progress("All sent")9233break9234m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],9235blocking=True,9236timeout=1)9237if m is None:9238continue92399240if m.get_type() == 'MISSION_ACK':9241if (m.target_system == 255 and9242m.target_component == 0 and9243m.type == 1 and9244m.mission_type == 0):9245# this is just MAVProxy trying to screw us up9246continue9247raise NotAchievedException(f"Received unexpected mission ack {self.dump_message_verbose(m)}")92489249self.progress("Handling request for item %u/%u" % (m.seq, len(items)-1))9250self.progress("Item (%s)" % str(items[m.seq]))9251if m.seq in sent:9252self.progress("received duplicate request for item %u" % m.seq)9253continue92549255if m.seq not in remaining_to_send:9256raise NotAchievedException("received request for unknown item %u" % m.seq)92579258if m.mission_type != mission_type:9259raise NotAchievedException("received request for item from wrong mission type")92609261if items[m.seq].mission_type != mission_type:9262raise NotAchievedException(f"supplied item not of correct mission type (want={mission_type} got={items[m.seq].mission_type}") # noqa:5019263if items[m.seq].target_system != target_system:9264raise NotAchievedException("supplied item not of correct target system")9265if items[m.seq].target_component != target_component:9266raise NotAchievedException("supplied item not of correct target component")9267if items[m.seq].seq != m.seq:9268raise NotAchievedException("supplied item has incorrect sequence number (%u vs %u)" %9269(items[m.seq].seq, m.seq))92709271items[m.seq].pack(self.mav.mav)9272self.mav.mav.send(items[m.seq])9273remaining_to_send.discard(m.seq)9274sent.add(m.seq)92759276timeout += 10 # we received a good request for item; be generous with our timeouts92779278m = self.assert_receive_message('MISSION_ACK', timeout=1)9279if m.mission_type != mission_type:9280raise NotAchievedException("Mission ack not of expected mission type")9281if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:9282raise NotAchievedException("Mission upload failed (%s)" %9283(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),)9284self.progress("Upload of all %u items succeeded" % len(items))92859286def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10):9287'''mavlink2 required'''9288target_system = 19289target_component = 19290self.progress("Sending mission_request_list")9291tstart = self.get_sim_time()9292self.mav.mav.mission_request_list_send(target_system,9293target_component,9294mission_type)92959296while True:9297if self.get_sim_time_cached() - tstart > timeout:9298raise NotAchievedException("Did not get MISSION_COUNT packet")9299m = self.mav.recv_match(blocking=True, timeout=0.1)9300if m is None:9301raise NotAchievedException("Did not get MISSION_COUNT response")9302if verbose:9303self.progress(str(m))9304if m.get_type() == 'MISSION_ACK':9305if m.target_system == 255 and m.target_component == 0:9306# this was for MAVProxy9307continue9308self.progress("Mission ACK: %s" % str(m))9309raise NotAchievedException("Received MISSION_ACK while waiting for MISSION_COUNT")9310if m.get_type() != 'MISSION_COUNT':9311continue9312if m.target_component != self.mav.source_system:9313continue9314if m.mission_type != mission_type:9315raise NotAchievedException("Mission count response of incorrect type")9316break93179318items = []9319tstart = self.get_sim_time_cached()9320remaining_to_receive = set(range(0, m.count))9321next_to_request = 09322timeout = m.count9323timeout *= self.speedup / 10.09324timeout += 109325while True:9326delta_t = self.get_sim_time_cached() - tstart9327if delta_t > timeout:9328raise NotAchievedException(9329"timeout downloading type=%s after %s seconds of %s allowed" %9330(mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name,9331delta_t, timeout))9332if len(remaining_to_receive) == 0:9333self.progress("All received")9334return items9335self.progress("Requesting item %u (remaining=%u)" %9336(next_to_request, len(remaining_to_receive)))9337self.mav.mav.mission_request_int_send(target_system,9338target_component,9339next_to_request,9340mission_type)9341m = self.mav.recv_match(type='MISSION_ITEM_INT',9342blocking=True,9343timeout=5,9344condition='MISSION_ITEM_INT.mission_type==%u' % mission_type)9345if m is None:9346raise NotAchievedException("Did not receive MISSION_ITEM_INT")9347if m.target_system != self.mav.source_system:9348raise NotAchievedException("Wrong target system (want=%u got=%u)" %9349(self.mav.source_system, m.target_system))9350if m.target_component != self.mav.source_component:9351raise NotAchievedException("Wrong target component")9352self.progress("Got (%s)" % str(m))9353if m.mission_type != mission_type:9354raise NotAchievedException("Received waypoint of wrong type")9355if m.seq != next_to_request:9356raise NotAchievedException("Received waypoint is out of sequence")9357self.progress("Item %u OK" % m.seq)9358timeout += 10 # we received an item; be generous with our timeouts9359items.append(m)9360next_to_request += 19361remaining_to_receive.discard(m.seq)93629363def dump_message_verbose(self, m):9364'''return verbose dump of m. Wraps the pymavlink routine which9365inconveniently takes a filehandle'''9366f = StringIO.StringIO()9367mavutil.dump_message_verbose(f, m)9368return f.getvalue()93699370def poll_home_position(self, quiet=True, timeout=30):9371old = self.mav.messages.get("HOME_POSITION", None)9372tstart = self.get_sim_time()9373while True:9374if self.get_sim_time_cached() - tstart > timeout:9375raise NotAchievedException("Failed to poll home position")9376if not quiet:9377self.progress("Sending MAV_CMD_GET_HOME_POSITION")9378try:9379self.run_cmd(9380mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,9381quiet=quiet,9382)9383except ValueError:9384continue9385m = self.mav.messages.get("HOME_POSITION", None)9386if m is None:9387continue9388if old is None:9389break9390if m._timestamp != old._timestamp:9391break9392self.progress("Polled home position (%s)" % str(m))9393return m93949395def position_target_loc(self):9396'''returns target location based on POSITION_TARGET_GLOBAL_INT'''9397m = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)9398return mavutil.location(m.lat_int*1e-7, m.lon_int*1e-7, m.alt)93999400def current_waypoint(self):9401m = self.assert_receive_message('MISSION_CURRENT')9402return m.seq94039404def distance_to_nav_target(self, use_cached_nav_controller_output=False):9405'''returns distance to waypoint navigation target in metres'''9406m = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None)9407if m is None or not use_cached_nav_controller_output:9408m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=10)9409return m.wp_dist94109411def distance_to_home(self, use_cached_home=False):9412m = self.mav.messages.get("HOME_POSITION", None)9413if use_cached_home is False or m is None:9414m = self.poll_home_position(quiet=True)9415here = self.assert_receive_message('GLOBAL_POSITION_INT')9416return self.get_distance_int(m, here)94179418def home_position_as_mav_location(self):9419m = self.poll_home_position()9420return mavutil.location(m.latitude*1.0e-7, m.longitude*1.0e-7, m.altitude*1.0e-3, 0)94219422def offset_location_ne(self, location, metres_north, metres_east):9423'''return a new location offset from passed-in location'''9424(target_lat, target_lng) = mavextra.gps_offset(location.lat,9425location.lng,9426metres_east,9427metres_north)9428return mavutil.location(target_lat,9429target_lng,9430location.alt,9431location.heading)94329433def offset_location_heading_distance(self, location, bearing, distance):9434(target_lat, target_lng) = mavextra.gps_newpos(9435location.lat,9436location.lng,9437bearing,9438distance9439)9440return mavutil.location(9441target_lat,9442target_lng,9443location.alt,9444location.heading9445)94469447def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):9448tstart = self.get_sim_time()9449while True:9450if self.get_sim_time_cached() - tstart > timeout:9451break9452m = self.assert_receive_message('VFR_HUD', timeout=timeout)9453if m.groundspeed > want+tolerance:9454raise NotAchievedException("Too fast (%f > %f)" %9455(m.groundspeed, want))9456if m.groundspeed < want-tolerance:9457raise NotAchievedException("Too slow (%f < %f)" %9458(m.groundspeed, want))9459self.progress("GroundSpeed OK (got=%f) (want=%f)" %9460(m.groundspeed, want))94619462def set_home(self, loc):9463'''set home to supplied loc'''9464self.run_cmd_int(9465mavutil.mavlink.MAV_CMD_DO_SET_HOME,9466p5=int(loc.lat*1e7),9467p6=int(loc.lng*1e7),9468p7=loc.alt,9469)94709471def SetHome(self):9472'''Setting and fetching of home'''9473if self.is_tracker():9474# tracker starts armed...9475self.disarm_vehicle(force=True)9476self.reboot_sitl()94779478# HOME_POSITION is used as a surrogate for origin until we9479# start emitting GPS_GLOBAL_ORIGIN9480self.wait_ekf_happy()9481orig_home = self.poll_home_position()9482if orig_home is None:9483raise AutoTestTimeoutException()9484self.progress("Original home: %s" % str(orig_home))9485# original home should be close to SITL home...9486start_loc = self.sitl_start_location()9487self.progress("SITL start loc: %s" % str(start_loc))9488delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)9489if delta > 0.000006:9490raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %9491(orig_home.latitude * 1.0e-7, start_loc.lat, delta))9492delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)9493if delta > 0.000006:9494raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %9495(orig_home.longitude * 1.0e-7, start_loc.lng, delta))9496if self.is_rover():9497self.progress("### Rover skipping altitude check unti position fixes in")9498else:9499home_alt_m = orig_home.altitude * 1.0e-39500if abs(home_alt_m - start_loc.alt) > 2: # metres9501raise ValueError("homes differ in alt got=%fm want=%fm" %9502(home_alt_m, start_loc.alt))9503new_x = orig_home.latitude + 10009504new_y = orig_home.longitude + 20009505new_z = orig_home.altitude + 300000 # 300 metres9506print("new home: %s %s %s" % (str(new_x), str(new_y), str(new_z)))9507self.run_cmd_int(9508mavutil.mavlink.MAV_CMD_DO_SET_HOME,9509p5=new_x,9510p6=new_y,9511p7=new_z/1000.0, # mm => m9512)95139514home = self.poll_home_position()9515self.progress("home: %s" % str(home))9516got_home_latitude = home.latitude9517got_home_longitude = home.longitude9518got_home_altitude = home.altitude9519if (got_home_latitude != new_x or9520got_home_longitude != new_y or9521abs(got_home_altitude - new_z) > 100): # float-conversion issues9522self.reboot_sitl()9523raise NotAchievedException(9524"Home mismatch got=(%f, %f, %f) set=(%f, %f, %f)" %9525(got_home_latitude, got_home_longitude, got_home_altitude,9526new_x, new_y, new_z))95279528self.progress("monitoring home to ensure it doesn't drift at all")9529tstart = self.get_sim_time()9530while self.get_sim_time_cached() - tstart < 10:9531home = self.poll_home_position(quiet=True)9532self.progress("home: %s" % str(home))9533if (home.latitude != got_home_latitude or9534home.longitude != got_home_longitude or9535home.altitude != got_home_altitude): # float-conversion issues9536self.reboot_sitl()9537raise NotAchievedException("home is drifting")95389539self.progress("Waiting for EKF to start")9540self.wait_ready_to_arm()9541self.progress("now use lat=0, lon=0 to reset home to current location")9542self.run_cmd_int(9543mavutil.mavlink.MAV_CMD_DO_SET_HOME,9544p5=0, # lat9545p6=0, # lon9546p7=new_z/1000.0, # mm => m9547)9548home = self.poll_home_position()9549self.progress("home: %s" % str(home))9550if self.distance_to_home(use_cached_home=True) > 1:9551raise NotAchievedException("Setting home to current location did not work")95529553self.progress("Setting home elsewhere again")9554self.run_cmd_int(9555mavutil.mavlink.MAV_CMD_DO_SET_HOME,9556p5=new_x,9557p6=new_y,9558p7=new_z/1000.0, # mm => m9559)9560if self.distance_to_home() < 10:9561raise NotAchievedException("Setting home to location did not work")95629563self.progress("use param1=1 to reset home to current location")9564self.run_cmd_int(9565mavutil.mavlink.MAV_CMD_DO_SET_HOME,9566p1=1, # use current location9567p5=37, # lat9568p6=21, # lon9569p7=new_z/1000.0, # mm => m9570)9571home = self.poll_home_position()9572self.progress("home: %s" % str(home))9573if self.distance_to_home() > 1:9574raise NotAchievedException("Setting home to current location did not work")95759576if self.is_tracker():9577# tracker starts armed...9578self.disarm_vehicle(force=True)9579self.reboot_sitl()95809581def zero_mag_offset_parameters(self, compass_count=3):9582self.progress("Zeroing Mag OFS parameters")9583self.get_sim_time()9584zero_offset_parameters_hash = {}9585for num in "", "2", "3":9586for axis in "X", "Y", "Z":9587name = "COMPASS_OFS%s_%s" % (num, axis)9588zero_offset_parameters_hash[name] = 09589self.set_parameters(zero_offset_parameters_hash)9590# force-save the calibration values:9591self.run_cmd_int(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, p2=76)9592self.progress("zeroed mag parameters")95939594params = [9595[("SIM_MAG1_OFS1_X", "COMPASS_OFS_X", 0),9596("SIM_MAG1_OFS1_Y", "COMPASS_OFS_Y", 0),9597("SIM_MAG1_OFS1_Z", "COMPASS_OFS_Z", 0), ],9598]9599for count in range(2, compass_count + 1):9600params += [9601[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, 0),9602("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, 0),9603("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, 0), ],9604]9605self.check_zero_mag_parameters(params)96069607def forty_two_mag_dia_odi_parameters(self, compass_count=3):9608self.progress("Forty twoing Mag DIA and ODI parameters")9609self.get_sim_time()9610params = [9611[("SIM_MAG1_DIA_X", "COMPASS_DIA_X", 42.0),9612("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", 42.0),9613("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", 42.0),9614("SIM_MAG1_ODI_X", "COMPASS_ODI_X", 42.0),9615("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", 42.0),9616("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", 42.0), ],9617]9618for count in range(2, compass_count + 1):9619params += [9620[("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, 42.0),9621("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, 42.0),9622("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, 42.0),9623("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, 42.0),9624("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, 42.0),9625("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, 42.0), ],9626]9627self.wait_heartbeat()9628to_set = {}9629for param_set in params:9630for param in param_set:9631(_, _out, value) = param9632to_set[_out] = value9633self.set_parameters(to_set)9634self.check_zero_mag_parameters(params)96359636def check_mag_parameters(self, parameter_stuff, compass_number):9637self.progress("Checking that Mag parameter")9638for idx in range(0, compass_number, 1):9639for param in parameter_stuff[idx]:9640(_in, _out, value) = param9641got_value = self.get_parameter(_out)9642if abs(got_value - value) > abs(value) * 0.15:9643raise NotAchievedException("%s/%s not within 15%%; got %f want=%f" % (_in, _out, got_value, value))96449645def check_zero_mag_parameters(self, parameter_stuff):9646self.progress("Checking that Mag OFS are zero")9647for param_set in parameter_stuff:9648for param in param_set:9649(_in, _out, _) = param9650got_value = self.get_parameter(_out)9651max = 0.159652if "DIA" in _out or "ODI" in _out:9653max += 42.09654if abs(got_value) > max:9655raise NotAchievedException(9656"%s/%s not within 15%%; got %f want=%f" %9657(_in, _out, got_value, 0.0 if max > 1 else 42.0))96589659def check_zeros_mag_orient(self, compass_count=3):9660self.progress("zeroed mag parameters")9661self.verify_parameter_values({"COMPASS_ORIENT": 0})9662for count in range(2, compass_count + 1):9663self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0})96649665# this autotest appears to interfere with FixedYawCalibration, no idea why.9666def SITLCompassCalibration(self, compass_count=3, timeout=1000):9667'''Test Fixed Yaw Calibration"'''96689669timeout /= 89670timeout *= self.speedup96719672def reset_pos_and_start_magcal(mavproxy, tmask):9673mavproxy.send("sitl_stop\n")9674mavproxy.send("sitl_attitude 0 0 0\n")9675self.get_sim_time()9676self.run_cmd(9677mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,9678p1=tmask, # p1: mag_mask9679p2=0, # retry9680p3=0, # autosave9681p4=0, # delay9682want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,9683timeout=20,9684)9685mavproxy.send("sitl_magcal\n")96869687def do_prep_mag_cal_test(mavproxy, params):9688self.progress("Preparing the vehicle for magcal")9689MAG_OFS = 1009690MAG_DIA = 1.09691MAG_ODI = 0.0049692params += [9693[("SIM_MAG1_OFS_X", "COMPASS_OFS_X", MAG_OFS),9694("SIM_MAG1_OFS_Y", "COMPASS_OFS_Y", MAG_OFS + 100),9695("SIM_MAG1_OFS_Z", "COMPASS_OFS_Z", MAG_OFS + 200),9696("SIM_MAG1_DIA_X", "COMPASS_DIA_X", MAG_DIA),9697("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", MAG_DIA + 0.1),9698("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", MAG_DIA + 0.2),9699("SIM_MAG1_ODI_X", "COMPASS_ODI_X", MAG_ODI),9700("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", MAG_ODI + 0.001),9701("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", MAG_ODI + 0.001), ],9702]9703for count in range(2, compass_count + 1):9704params += [9705[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),9706("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),9707("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),9708("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),9709("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),9710("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),9711("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),9712("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),9713("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],9714]9715self.progress("Setting calibration mode")9716self.wait_heartbeat()9717self.customise_SITL_commandline(["-M", "calibration"])9718self.mavproxy_load_module(mavproxy, "sitl_calibration")9719self.mavproxy_load_module(mavproxy, "calibration")9720self.mavproxy_load_module(mavproxy, "relay")9721self.wait_statustext("is using GPS", timeout=60)9722mavproxy.send("accelcalsimple\n")9723mavproxy.expect("Calibrated")9724# disable it to not interfert with calibration acceptation9725self.mavproxy_unload_module(mavproxy, "calibration")9726if self.is_copter():9727# set frame class to pass arming check on copter9728self.set_parameter("FRAME_CLASS", 1)9729self.progress("Setting SITL Magnetometer model value")9730self.set_parameter("COMPASS_AUTO_ROT", 0)9731# MAG_ORIENT = 49732# self.set_parameter("SIM_MAG1_ORIENT", MAG_ORIENT)9733# for count in range(2, compass_count + 1):9734# self.set_parameter("SIM_MAG%d_ORIENT" % count, MAG_ORIENT * (count % 41))9735# # set compass external to check that orientation is found and auto set9736# self.set_parameter("COMPASS_EXTERN%d" % count, 1)9737to_set = {}9738for param_set in params:9739for param in param_set:9740(_in, _out, value) = param9741to_set[_in] = value9742to_set[_out] = value9743self.set_parameters(to_set)9744self.start_subtest("Zeroing Mag OFS parameters with Mavlink")9745self.zero_mag_offset_parameters()9746self.progress("=========================================")9747# Change the default value to unexpected 429748self.forty_two_mag_dia_odi_parameters()9749self.progress("Zeroing Mags orientations")9750self.set_parameter("COMPASS_ORIENT", 0)9751for count in range(2, compass_count + 1):9752self.set_parameter("COMPASS_ORIENT%d" % count, 0)97539754# Only care about compass prearm9755self.set_parameter("ARMING_CHECK", 4)97569757#################################################9758def do_test_mag_cal(mavproxy, params, compass_tnumber):9759self.start_subtest("Try magcal and make it stop around 30%")9760self.progress("Compass mask is %s" % "{0:b}".format(target_mask))9761reset_pos_and_start_magcal(mavproxy, target_mask)9762tstart = self.get_sim_time()9763reached_pct = [0] * compass_tnumber9764tstop = None9765while True:9766if self.get_sim_time_cached() - tstart > timeout:9767raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")9768m = self.mav.recv_match(type='MAG_CAL_PROGRESS', blocking=True, timeout=5)9769if m is None:9770if tstop is not None:9771# wait 3 second to unsure that the calibration is well stopped9772if self.get_sim_time_cached() - tstop > 10:9773if reached_pct[0] > 33:9774raise NotAchievedException("Mag calibration didn't stop")9775else:9776break9777else:9778continue9779else:9780continue9781if m is not None:9782self.progress("Mag CAL progress: %s" % str(m))9783cid = m.compass_id9784new_pct = int(m.completion_pct)9785if new_pct != reached_pct[cid]:9786if new_pct < reached_pct[cid]:9787raise NotAchievedException("Mag calibration restart when it shouldn't")9788reached_pct[cid] = new_pct9789self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))9790if cid == 0 and 13 <= reached_pct[0] <= 15:9791self.progress("Request again to start calibration, it shouldn't restart from 0")9792self.run_cmd(9793mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,9794p1=target_mask,9795want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,9796timeout=20,9797)97989799if reached_pct[0] > 30:9800self.run_cmd(9801mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,9802p1=target_mask,9803want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,9804)9805if tstop is None:9806tstop = self.get_sim_time_cached()9807if tstop is not None:9808# wait 3 second to unsure that the calibration is well stopped9809if self.get_sim_time_cached() - tstop > 3:9810raise NotAchievedException("Mag calibration didn't stop")9811self.check_zero_mag_parameters(params)9812self.check_zeros_mag_orient()98139814#################################################9815self.start_subtest("Try magcal and make it failed")9816self.progress("Compass mask is %s" % "{0:b}".format(target_mask))9817old_cal_fit = self.get_parameter("COMPASS_CAL_FIT")9818self.set_parameter("COMPASS_CAL_FIT", 0.001, add_to_context=False)9819reset_pos_and_start_magcal(mavproxy, target_mask)9820tstart = self.get_sim_time()9821reached_pct = [0] * compass_tnumber9822report_get = [0] * compass_tnumber9823while True:9824if self.get_sim_time_cached() - tstart > timeout:9825raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")9826m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=10)9827if m.get_type() == "MAG_CAL_REPORT":9828if report_get[m.compass_id] == 0:9829self.progress("Report: %s" % str(m))9830if m.cal_status == mavutil.mavlink.MAG_CAL_FAILED:9831report_get[m.compass_id] = 19832else:9833raise NotAchievedException("Mag calibration didn't failed")9834if all(ele >= 1 for ele in report_get):9835self.progress("All Mag report failure")9836break9837if m is not None and m.get_type() == "MAG_CAL_PROGRESS":9838self.progress("Mag CAL progress: %s" % str(m))9839cid = m.compass_id9840new_pct = int(m.completion_pct)9841if new_pct != reached_pct[cid]:9842reached_pct[cid] = new_pct9843self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))9844if cid == 0 and 49 <= reached_pct[0] <= 50:9845self.progress("Try arming during calibration, should failed")9846self.try_arm(False, "Compass calibration running")98479848self.check_zero_mag_parameters(params)9849self.check_zeros_mag_orient()9850self.set_parameter("COMPASS_CAL_FIT", old_cal_fit, add_to_context=False)98519852#################################################9853self.start_subtest("Try magcal and wait success")9854self.progress("Compass mask is %s" % "{0:b}".format(target_mask))9855reset_pos_and_start_magcal(mavproxy, target_mask)9856progress_count = [0] * compass_tnumber9857reached_pct = [0] * compass_tnumber9858report_get = [0] * compass_tnumber9859tstart = self.get_sim_time()9860while True:9861if self.get_sim_time_cached() - tstart > timeout:9862raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")9863m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=5)9864if m.get_type() == "MAG_CAL_REPORT":9865if report_get[m.compass_id] == 0:9866self.progress("Report: %s" % self.dump_message_verbose(m))9867param_names = ["SIM_MAG1_ORIENT"]9868for i in range(2, compass_tnumber+1):9869param_names.append("SIM_MAG%u_ORIENT" % i)9870for param_name in param_names:9871self.progress("%s=%f" % (param_name, self.get_parameter(param_name)))9872if m.cal_status == mavutil.mavlink.MAG_CAL_SUCCESS:9873threshold = 959874if reached_pct[m.compass_id] < threshold:9875raise NotAchievedException(9876"Mag calibration report SUCCESS without >=%f%% completion (got %f%%)" %9877(threshold, reached_pct[m.compass_id]))9878report_get[m.compass_id] = 19879else:9880raise NotAchievedException(9881"Mag calibration didn't SUCCEED (cal_status=%u) (progress_count=%s)" %9882(m.cal_status, progress_count[m.compass_id],))9883if all(ele >= 1 for ele in report_get):9884self.progress("All Mag report SUCCESS")9885break9886if m is not None and m.get_type() == "MAG_CAL_PROGRESS":9887cid = m.compass_id9888new_pct = int(m.completion_pct)9889progress_count[cid] += 19890if new_pct != reached_pct[cid]:9891reached_pct[cid] = new_pct9892self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))9893mavproxy.send("sitl_stop\n")9894mavproxy.send("sitl_attitude 0 0 0\n")9895self.progress("Checking that value aren't changed without acceptation")9896self.check_zero_mag_parameters(params)9897self.check_zeros_mag_orient()9898self.progress("Send acceptation and check value")9899self.wait_heartbeat()9900self.run_cmd(9901mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,9902p1=target_mask, # p1: mag_mask9903want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,9904timeout=20,9905)9906self.check_mag_parameters(params, compass_tnumber)9907self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG1_ORIENT")})9908for count in range(2, compass_tnumber + 1):9909self.verify_parameter_values({"COMPASS_ORIENT%d" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})9910self.try_arm(False, "Compass calibrated requires reboot")99119912# test buzzer/notify ?9913self.progress("Rebooting and making sure we could arm with these values")9914self.drain_mav()9915self.reboot_sitl()9916if False: # FIXME! This fails with compasses inconsistent!9917self.wait_ready_to_arm(timeout=60)9918self.progress("Setting manually the parameter for other sensor to avoid compass consistency error")9919for idx in range(compass_tnumber, compass_count, 1):9920for param in params[idx]:9921(_in, _out, value) = param9922self.set_parameter(_out, value)9923for count in range(compass_tnumber + 1, compass_count + 1):9924self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))9925self.arm_vehicle()9926self.progress("Test calibration rejection when armed")9927self.run_cmd(9928mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,9929p1=target_mask, # p1: mag_mask9930p2=0, # retry9931p3=0, # autosave9932p4=0, # delay9933want_result=mavutil.mavlink.MAV_RESULT_FAILED,9934timeout=20,9935)9936self.disarm_vehicle()9937self.mavproxy_unload_module(mavproxy, "relay")9938self.mavproxy_unload_module(mavproxy, "sitl_calibration")99399940ex = None99419942mavproxy = self.start_mavproxy()9943try:9944self.set_parameter("AHRS_EKF_TYPE", 10)9945self.set_parameter("SIM_GND_BEHAV", 0)99469947curr_params = []9948target_mask = 09949# we test all bitmask plus 0 for all9950for run in range(-1, compass_count, 1):9951ntest_compass = compass_count9952if run < 0:9953# use bitmask 0 for all compass9954target_mask = 09955else:9956target_mask |= (1 << run)9957ntest_compass = run + 19958do_prep_mag_cal_test(mavproxy, curr_params)9959do_test_mag_cal(mavproxy, curr_params, ntest_compass)99609961except Exception as e:9962self.progress("Caught exception: %s" %9963self.get_exception_stacktrace(e))9964ex = e9965self.mavproxy_unload_module(mavproxy, "relay")9966self.mavproxy_unload_module(mavproxy, "sitl_calibration")9967if ex is not None:9968raise ex99699970self.stop_mavproxy(mavproxy)99719972# need to reboot SITL after moving away from EKF type 10; we9973# can end up with home set but origin not and that will lead9974# to bad things.9975self.reboot_sitl()99769977def test_mag_reordering_assert_mag_transform(self, values, transforms):9978'''transforms ought to be read as, "take all the parameter values from9979the first compass parameters and shove them into the second indicating9980compass parameters'''99819982# create a set of mappings from one parameter name to another9983# e.g. COMPASS_OFS_X => COMPASS_OFS2_X if the transform is9984# [(1,2)]. [(1,2),(2,1)] should swap the compass values99859986parameter_mappings = {}9987for key in values.keys():9988parameter_mappings[key] = key9989for (old_compass_num, new_compass_num) in transforms:9990old_key_compass_bit = str(old_compass_num)9991if old_key_compass_bit == "1":9992old_key_compass_bit = ""9993new_key_compass_bit = str(new_compass_num)9994if new_key_compass_bit == "1":9995new_key_compass_bit = ""9996# vectors first:9997for key_vector_bit in ["OFS", "DIA", "ODI", "MOT"]:9998for axis in "X", "Y", "Z":9999old_key = "COMPASS_%s%s_%s" % (key_vector_bit,10000old_key_compass_bit,10001axis)10002new_key = "COMPASS_%s%s_%s" % (key_vector_bit,10003new_key_compass_bit,10004axis)10005parameter_mappings[old_key] = new_key10006# then non-vectorey bits:10007for key_bit in "SCALE", "ORIENT":10008old_key = "COMPASS_%s%s" % (key_bit, old_key_compass_bit)10009new_key = "COMPASS_%s%s" % (key_bit, new_key_compass_bit)10010parameter_mappings[old_key] = new_key10011# then a sore thumb:10012if old_key_compass_bit == "":10013old_key = "COMPASS_EXTERNAL"10014else:10015old_key = "COMPASS_EXTERN%s" % old_key_compass_bit10016if new_key_compass_bit == "":10017new_key = "COMPASS_EXTERNAL"10018else:10019new_key = "COMPASS_EXTERN%s" % new_key_compass_bit10020parameter_mappings[old_key] = new_key1002110022for key in values.keys():10023newkey = parameter_mappings[key]10024current_value = self.get_parameter(newkey)10025expected_value = values[key]10026if abs(current_value - expected_value) > 0.001:10027raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" %10028(newkey, expected_value, current_value, str(transforms), key))1002910030def CompassReordering(self):10031'''Test Compass reordering when priorities are changed'''10032self.context_push()10033ex = None10034try:10035originals = {10036"COMPASS_OFS_X": 1.1,10037"COMPASS_OFS_Y": 1.2,10038"COMPASS_OFS_Z": 1.3,10039"COMPASS_DIA_X": 1.4,10040"COMPASS_DIA_Y": 1.5,10041"COMPASS_DIA_Z": 1.6,10042"COMPASS_ODI_X": 1.7,10043"COMPASS_ODI_Y": 1.8,10044"COMPASS_ODI_Z": 1.9,10045"COMPASS_MOT_X": 1.91,10046"COMPASS_MOT_Y": 1.92,10047"COMPASS_MOT_Z": 1.93,10048"COMPASS_SCALE": 1.94,10049"COMPASS_ORIENT": 1,10050"COMPASS_EXTERNAL": 2,1005110052"COMPASS_OFS2_X": 2.1,10053"COMPASS_OFS2_Y": 2.2,10054"COMPASS_OFS2_Z": 2.3,10055"COMPASS_DIA2_X": 2.4,10056"COMPASS_DIA2_Y": 2.5,10057"COMPASS_DIA2_Z": 2.6,10058"COMPASS_ODI2_X": 2.7,10059"COMPASS_ODI2_Y": 2.8,10060"COMPASS_ODI2_Z": 2.9,10061"COMPASS_MOT2_X": 2.91,10062"COMPASS_MOT2_Y": 2.92,10063"COMPASS_MOT2_Z": 2.93,10064"COMPASS_SCALE2": 2.94,10065"COMPASS_ORIENT2": 3,10066"COMPASS_EXTERN2": 4,1006710068"COMPASS_OFS3_X": 3.1,10069"COMPASS_OFS3_Y": 3.2,10070"COMPASS_OFS3_Z": 3.3,10071"COMPASS_DIA3_X": 3.4,10072"COMPASS_DIA3_Y": 3.5,10073"COMPASS_DIA3_Z": 3.6,10074"COMPASS_ODI3_X": 3.7,10075"COMPASS_ODI3_Y": 3.8,10076"COMPASS_ODI3_Z": 3.9,10077"COMPASS_MOT3_X": 3.91,10078"COMPASS_MOT3_Y": 3.92,10079"COMPASS_MOT3_Z": 3.93,10080"COMPASS_SCALE3": 3.94,10081"COMPASS_ORIENT3": 5,10082"COMPASS_EXTERN3": 6,10083}1008410085# quick sanity check to ensure all values are unique:10086if len(originals.values()) != len(set(originals.values())):10087raise NotAchievedException("Values are not all unique!")1008810089self.progress("Setting parameters")10090self.set_parameters(originals)1009110092self.reboot_sitl()1009310094# no transforms means our originals should be our finals:10095self.test_mag_reordering_assert_mag_transform(originals, [])1009610097self.start_subtest("Pushing 1st mag to 3rd")10098ey = None10099self.context_push()10100try:10101# now try reprioritising compass 1 to be higher than compass 0:10102prio1_id = self.get_parameter("COMPASS_PRIO1_ID")10103prio2_id = self.get_parameter("COMPASS_PRIO2_ID")10104prio3_id = self.get_parameter("COMPASS_PRIO3_ID")10105self.set_parameter("COMPASS_PRIO1_ID", prio2_id)10106self.set_parameter("COMPASS_PRIO2_ID", prio3_id)10107self.set_parameter("COMPASS_PRIO3_ID", prio1_id)1010810109self.reboot_sitl()1011010111self.test_mag_reordering_assert_mag_transform(originals, [(2, 1),10112(3, 2),10113(1, 3)])1011410115except Exception as e:10116self.progress("Caught exception: %s" %10117self.get_exception_stacktrace(e))10118ey = e10119self.context_pop()10120self.reboot_sitl()10121if ey is not None:10122raise ey1012310124except Exception as e:10125self.progress("Caught exception: %s" %10126self.get_exception_stacktrace(e))10127ex = e10128self.context_pop()10129self.reboot_sitl()10130if ex is not None:10131raise ex1013210133# something about SITLCompassCalibration appears to fail10134# this one, so we put it first:10135def FixedYawCalibration(self):10136'''Test Fixed Yaw Calibration'''10137self.context_push()10138ex = None10139try:10140MAG_OFS_X = 10010141MAG_OFS_Y = 20010142MAG_OFS_Z = 30010143wanted = {10144"COMPASS_OFS_X": (MAG_OFS_X, 3.0),10145"COMPASS_OFS_Y": (MAG_OFS_Y, 3.0),10146"COMPASS_OFS_Z": (MAG_OFS_Z, 3.0),10147"COMPASS_DIA_X": 1,10148"COMPASS_DIA_Y": 1,10149"COMPASS_DIA_Z": 1,10150"COMPASS_ODI_X": 0,10151"COMPASS_ODI_Y": 0,10152"COMPASS_ODI_Z": 0,1015310154"COMPASS_OFS2_X": (MAG_OFS_X, 3.0),10155"COMPASS_OFS2_Y": (MAG_OFS_Y, 3.0),10156"COMPASS_OFS2_Z": (MAG_OFS_Z, 3.0),10157"COMPASS_DIA2_X": 1,10158"COMPASS_DIA2_Y": 1,10159"COMPASS_DIA2_Z": 1,10160"COMPASS_ODI2_X": 0,10161"COMPASS_ODI2_Y": 0,10162"COMPASS_ODI2_Z": 0,1016310164"COMPASS_OFS3_X": (MAG_OFS_X, 3.0),10165"COMPASS_OFS3_Y": (MAG_OFS_Y, 3.0),10166"COMPASS_OFS3_Z": (MAG_OFS_Z, 3.0),10167"COMPASS_DIA3_X": 1,10168"COMPASS_DIA3_Y": 1,10169"COMPASS_DIA3_Z": 1,10170"COMPASS_ODI3_X": 0,10171"COMPASS_ODI3_Y": 0,10172"COMPASS_ODI3_Z": 0,10173}10174self.set_parameters({10175"SIM_MAG1_OFS_X": MAG_OFS_X,10176"SIM_MAG1_OFS_Y": MAG_OFS_Y,10177"SIM_MAG1_OFS_Z": MAG_OFS_Z,1017810179"SIM_MAG2_OFS_X": MAG_OFS_X,10180"SIM_MAG2_OFS_Y": MAG_OFS_Y,10181"SIM_MAG2_OFS_Z": MAG_OFS_Z,1018210183"SIM_MAG3_OFS_X": MAG_OFS_X,10184"SIM_MAG3_OFS_Y": MAG_OFS_Y,10185"SIM_MAG3_OFS_Z": MAG_OFS_Z,10186})1018710188# set to some sensible-ish initial values. If your initial10189# offsets are way, way off you can get some very odd effects.10190for param in wanted:10191value = 0.010192if "DIA" in param:10193value = 1.00110194elif "ODI" in param:10195value = 0.00110196self.set_parameter(param, value)1019710198self.zero_mag_offset_parameters()1019910200# wait until we definitely know where we are:10201self.poll_home_position(timeout=120)1020210203ss = self.assert_receive_message('SIMSTATE', timeout=1, verbose=True)1020410205self.run_cmd(10206mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,10207p1=math.degrees(ss.yaw),10208)10209self.verify_parameter_values(wanted)1021010211# run same command but as command_int:10212self.zero_mag_offset_parameters()10213self.run_cmd_int(10214mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,10215p1=math.degrees(ss.yaw),10216)10217self.verify_parameter_values(wanted)1021810219self.progress("Rebooting and making sure we could arm with these values")10220self.reboot_sitl()10221self.wait_ready_to_arm(timeout=60)1022210223except Exception as e:10224ex = e1022510226self.context_pop()1022710228if ex is not None:10229raise ex1023010231def DataFlashOverMAVLink(self):10232'''Test DataFlash over MAVLink'''10233self.context_push()10234ex = None10235mavproxy = self.start_mavproxy()10236try:10237self.set_parameter("LOG_BACKEND_TYPE", 2)10238self.reboot_sitl()10239self.wait_ready_to_arm(check_prearm_bit=False)10240mavproxy.send('arm throttle\n')10241mavproxy.expect('PreArm: Logging failed')10242self.mavproxy_load_module(mavproxy, 'dataflash_logger')10243mavproxy.send("dataflash_logger set verbose 1\n")10244mavproxy.expect('logging started')10245mavproxy.send("dataflash_logger set verbose 0\n")10246self.delay_sim_time(1)10247self.do_timesync_roundtrip() # drain COMMAND_ACK from that failed arm10248self.arm_vehicle()10249tstart = self.get_sim_time()10250last_status = 010251mavproxy.send('repeat add 1 dataflash_logger status\n')10252while True:10253now = self.get_sim_time()10254if now - tstart > 60:10255break10256if now - last_status > 5:10257last_status = now10258# seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:010259mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")10260rate = float(mavproxy.match.group(1))10261self.progress("Rate: %f" % rate)10262desired_rate = 5010263if self.valgrind or self.callgrind:10264desired_rate /= 1010265if rate < desired_rate:10266raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))10267self.disarm_vehicle()10268mavproxy.send('repeat remove 0\n')10269except Exception as e:10270self.print_exception_caught(e)10271self.disarm_vehicle()10272ex = e10273self.mavproxy_unload_module(mavproxy, 'dataflash_logger')1027410275# the following things won't work - but they shouldn't die either:10276self.mavproxy_load_module(mavproxy, 'log')1027710278self.progress("Try log list")10279mavproxy.send("log list\n")10280mavproxy.expect("No logs")1028110282self.progress("Try log erase")10283mavproxy.send("log erase\n")10284# no response to this...1028510286self.progress("Try log download")10287mavproxy.send("log download 1\n")10288# no response to this...1028910290self.mavproxy_unload_module(mavproxy, 'log')1029110292self.context_pop()1029310294self.stop_mavproxy(mavproxy)10295self.reboot_sitl()10296if ex is not None:10297raise ex1029810299def DataFlash(self):10300"""Test DataFlash SITL backend"""10301self.context_push()10302ex = None10303mavproxy = self.start_mavproxy()10304try:10305self.set_parameter("LOG_BACKEND_TYPE", 4)10306self.set_parameter("LOG_FILE_DSRMROT", 1)10307self.set_parameter("LOG_BLK_RATEMAX", 1)10308self.reboot_sitl()10309# First log created here, but we are in chip erase so ignored10310mavproxy.send("module load log\n")10311mavproxy.send("log erase\n")10312mavproxy.expect("Chip erase complete")1031310314self.wait_ready_to_arm()10315if self.is_copter() or self.is_plane():10316self.set_autodisarm_delay(0)10317self.arm_vehicle()10318self.delay_sim_time(5)10319self.disarm_vehicle()10320# First log created here10321self.delay_sim_time(2)10322self.arm_vehicle()10323self.delay_sim_time(5)10324self.disarm_vehicle()10325# Second log created here10326self.delay_sim_time(2)10327mavproxy.send("log list\n")10328mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)10329log_num = int(mavproxy.match.group(1))10330numlogs = int(mavproxy.match.group(2))10331lastlog = int(mavproxy.match.group(3))10332size = int(mavproxy.match.group(4))10333if numlogs != 2 or log_num != 1 or size <= 0:10334raise NotAchievedException("Unexpected log information %d %d %d" % (log_num, numlogs, lastlog))10335self.progress("Log size: %d" % size)10336self.reboot_sitl()10337# This starts a new log with a time of 0, wait for arm so that we can insert the correct time10338self.wait_ready_to_arm()10339# Third log created here10340mavproxy.send("log list\n")10341mavproxy.expect("Log 1 numLogs 3 lastLog 3 size")1034210343# Download second and third logs10344mavproxy.send("log download 2 logs/dataflash-log-002.BIN\n")10345mavproxy.expect("Finished downloading", timeout=120)10346mavproxy.send("log download 3 logs/dataflash-log-003.BIN\n")10347mavproxy.expect("Finished downloading", timeout=120)1034810349# Erase the logs10350mavproxy.send("log erase\n")10351mavproxy.expect("Chip erase complete")1035210353except Exception as e:10354self.print_exception_caught(e)10355ex = e10356mavproxy.send("module unload log\n")10357self.stop_mavproxy(mavproxy)10358self.context_pop()10359self.reboot_sitl()10360if ex is not None:10361raise ex1036210363def validate_log_file(self, logname, header_errors=0):10364"""Validate the contents of a log file"""10365# read the downloaded log - it must parse without error10366class Capturing(list):10367def __enter__(self):10368self._stderr = sys.stderr10369sys.stderr = self._stringio = StringIO.StringIO()10370return self1037110372def __exit__(self, *args):10373self.extend(self._stringio.getvalue().splitlines())10374del self._stringio # free up some memory10375sys.stderr = self._stderr1037610377with Capturing() as df_output:10378try:10379mlog = mavutil.mavlink_connection(logname)10380while True:10381m = mlog.recv_match()10382if m is None:10383break10384except Exception as e:10385raise NotAchievedException("Error reading log file %s: %s" % (logname, str(e)))1038610387herrors = 01038810389for msg in df_output:10390if msg.startswith("bad header") or msg.startswith("unknown msg type"):10391herrors = herrors + 11039210393if herrors > header_errors:10394raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors))1039510396def DataFlashErase(self):10397"""Test that erasing the dataflash chip and creating a new log is error free"""10398mavproxy = self.start_mavproxy()1039910400ex = None10401self.context_push()10402try:10403self.set_parameter("LOG_BACKEND_TYPE", 4)10404self.reboot_sitl()10405mavproxy.send("module load log\n")10406mavproxy.send("log erase\n")10407mavproxy.expect("Chip erase complete")10408self.set_parameter("LOG_DISARMED", 1)10409self.delay_sim_time(3)10410self.set_parameter("LOG_DISARMED", 0)10411mavproxy.send("log download 1 logs/dataflash-log-erase.BIN\n")10412mavproxy.expect("Finished downloading", timeout=120)10413# read the downloaded log - it must parse without error10414self.validate_log_file("logs/dataflash-log-erase.BIN")1041510416self.start_subtest("Test file wrapping results in a valid file")10417# roughly 4mb10418self.set_parameter("LOG_FILE_DSRMROT", 1)10419self.set_parameter("LOG_BITMASK", 131071)10420self.wait_ready_to_arm()10421if self.is_copter() or self.is_plane():10422self.set_autodisarm_delay(0)10423self.arm_vehicle()10424self.delay_sim_time(30)10425self.disarm_vehicle()10426# roughly 4mb10427self.arm_vehicle()10428self.delay_sim_time(30)10429self.disarm_vehicle()10430# roughly 9mb, should wrap around10431self.arm_vehicle()10432self.delay_sim_time(50)10433self.disarm_vehicle()10434# make sure we have finished logging10435self.delay_sim_time(15)10436mavproxy.send("log list\n")10437try:10438mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)10439except pexpect.TIMEOUT as e:10440if self.sitl_is_running():10441self.progress("SITL is running")10442else:10443self.progress("SITL is NOT running")10444raise NotAchievedException("Received %s" % str(e))10445if int(mavproxy.match.group(2)) != 3:10446raise NotAchievedException("Expected 3 logs got %s" % (mavproxy.match.group(2)))1044710448mavproxy.send("log download 1 logs/dataflash-log-erase2.BIN\n")10449mavproxy.expect("Finished downloading", timeout=120)10450self.validate_log_file("logs/dataflash-log-erase2.BIN", 1)1045110452mavproxy.send("log download latest logs/dataflash-log-erase3.BIN\n")10453mavproxy.expect("Finished downloading", timeout=120)10454self.validate_log_file("logs/dataflash-log-erase3.BIN", 1)1045510456# clean up10457mavproxy.send("log erase\n")10458mavproxy.expect("Chip erase complete")1045910460# clean up10461mavproxy.send("log erase\n")10462mavproxy.expect("Chip erase complete")1046310464except Exception as e:10465self.print_exception_caught(e)10466ex = e1046710468mavproxy.send("module unload log\n")1046910470self.context_pop()10471self.reboot_sitl()1047210473self.stop_mavproxy(mavproxy)1047410475if ex is not None:10476raise ex1047710478def ArmFeatures(self):10479'''Arm features'''10480# TEST ARMING/DISARM10481self.delay_sim_time(12) # wait for gyros/accels to be happy10482if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub():10483raise ValueError("Arming check should be 1")10484if not self.is_sub() and not self.is_tracker():10485self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests10486if self.is_copter():10487interlock_channel = 8 # Plane got flighmode_ch on channel 810488if not self.is_heli(): # heli don't need interlock option10489interlock_channel = 910490self.set_parameter("RC%u_OPTION" % interlock_channel, 32)10491self.set_rc(interlock_channel, 1000)10492self.zero_throttle()10493# Disable auto disarm for next tests10494# Rover and Sub don't have auto disarm10495if self.is_copter() or self.is_plane():10496self.set_autodisarm_delay(0)10497self.start_subtest("Test normal arm and disarm features")10498self.wait_ready_to_arm()10499self.progress("default arm_vehicle() call")10500if not self.arm_vehicle():10501raise NotAchievedException("Failed to ARM")10502self.progress("default disarm_vehicle() call")10503self.disarm_vehicle()1050410505self.start_subtest("Arm/disarm vehicle with COMMAND_INT")10506self.run_cmd_int(10507mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10508p1=1, # ARM10509)10510self.run_cmd_int(10511mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10512p1=0, # DISARM10513)1051410515self.progress("arm with mavproxy")10516mavproxy = self.start_mavproxy()10517if not self.mavproxy_arm_vehicle(mavproxy):10518raise NotAchievedException("Failed to ARM")10519self.progress("disarm with mavproxy")10520self.mavproxy_disarm_vehicle(mavproxy)10521self.stop_mavproxy(mavproxy)1052210523if not self.is_sub():10524self.start_subtest("Test arm with rc input")10525self.arm_motors_with_rc_input()10526self.progress("disarm with rc input")10527if self.is_balancebot():10528self.progress("balancebot can't disarm with RC input")10529self.disarm_vehicle()10530else:10531self.disarm_motors_with_rc_input()1053210533self.start_subtest("Test arm and disarm with switch")10534arming_switch = 710535self.set_parameter("RC%d_OPTION" % arming_switch, 153)10536self.set_rc(arming_switch, 1000)10537# delay so a transition is seen by the RC switch code:10538self.delay_sim_time(0.5)10539self.arm_motors_with_switch(arming_switch)10540self.disarm_motors_with_switch(arming_switch)10541self.set_rc(arming_switch, 1000)1054210543if self.is_copter():10544self.start_subtest("Test arming failure with throttle too high")10545self.set_rc(3, 1800)10546try:10547if self.arm_vehicle():10548raise NotAchievedException("Armed when throttle too high")10549except ValueError:10550pass10551try:10552self.arm_motors_with_rc_input()10553except NotAchievedException:10554pass10555if self.armed():10556raise NotAchievedException(10557"Armed via RC when throttle too high")10558try:10559self.arm_motors_with_switch(arming_switch)10560except NotAchievedException:10561pass10562if self.armed():10563raise NotAchievedException("Armed via RC when switch too high")10564self.zero_throttle()10565self.set_rc(arming_switch, 1000)1056610567# Sub doesn't have 'stick commands'10568self.start_subtest("Test arming failure with ARMING_RUDDER=0")10569self.set_parameter("ARMING_RUDDER", 0)10570try:10571self.arm_motors_with_rc_input()10572except NotAchievedException:10573pass10574if self.armed():10575raise NotAchievedException(10576"Armed with rudder when ARMING_RUDDER=0")10577self.start_subtest("Test disarming failure with ARMING_RUDDER=0")10578self.arm_vehicle()10579try:10580self.disarm_motors_with_rc_input(watch_for_disabled=True)10581except NotAchievedException:10582pass10583if not self.armed():10584raise NotAchievedException(10585"Disarmed with rudder when ARMING_RUDDER=0")10586self.disarm_vehicle()10587self.wait_heartbeat()10588self.start_subtest("Test disarming failure with ARMING_RUDDER=1")10589self.set_parameter("ARMING_RUDDER", 1)10590self.arm_vehicle()10591try:10592self.disarm_motors_with_rc_input()10593except NotAchievedException:10594pass10595if not self.armed():10596raise NotAchievedException(10597"Disarmed with rudder with ARMING_RUDDER=1")10598self.disarm_vehicle()10599self.wait_heartbeat()10600self.set_parameter("ARMING_RUDDER", 2)1060110602if self.is_copter():10603self.start_subtest("Test arming failure with interlock enabled")10604self.set_rc(interlock_channel, 2000)10605try:10606self.arm_motors_with_rc_input()10607except NotAchievedException:10608pass10609if self.armed():10610raise NotAchievedException(10611"Armed with RC input when interlock enabled")10612try:10613self.arm_motors_with_switch(arming_switch)10614except NotAchievedException:10615pass10616if self.armed():10617raise NotAchievedException("Armed with switch when interlock enabled")10618self.disarm_vehicle()10619self.wait_heartbeat()10620self.set_rc(arming_switch, 1000)10621self.set_rc(interlock_channel, 1000)10622if self.is_heli():10623self.start_subtest("Test motor interlock enable can't be set while disarmed")10624self.set_rc(interlock_channel, 2000)10625channel_field = "servo%u_raw" % interlock_channel10626interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel)10627tstart = self.get_sim_time()10628while True:10629if self.get_sim_time_cached() - tstart > 20:10630self.set_rc(interlock_channel, 1000)10631break # success!10632m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',10633blocking=True,10634timeout=2)10635if m is None:10636continue10637m_value = getattr(m, channel_field, None)10638if m_value is None:10639self.set_rc(interlock_channel, 1000)10640raise ValueError("Message has no %s field" %10641channel_field)10642self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %10643(channel_field, m_value, interlock_value))10644if m_value != interlock_value:10645self.set_rc(interlock_channel, 1000)10646raise NotAchievedException("Motor interlock was changed while disarmed")10647self.set_rc(interlock_channel, 1000)1064810649self.start_subtest("Test all mode arming")10650self.wait_ready_to_arm()1065110652if self.arming_test_mission() is not None:10653self.load_mission(self.arming_test_mission())1065410655for mode in self.mav.mode_mapping():10656self.drain_mav()10657self.start_subtest("Mode : %s" % mode)10658if mode == "FOLLOW":10659self.set_parameter("FOLL_ENABLE", 1)10660if mode in self.get_normal_armable_modes_list():10661self.progress("Armable mode : %s" % mode)10662self.change_mode(mode)10663self.arm_vehicle()10664self.disarm_vehicle()10665self.progress("PASS arm mode : %s" % mode)10666if mode in self.get_not_armable_mode_list():10667if mode in self.get_not_disarmed_settable_modes_list():10668self.progress("Not settable mode : %s" % mode)10669try:10670self.change_mode(mode, timeout=15)10671except AutoTestTimeoutException:10672self.progress("PASS not able to set mode : %s disarmed" % mode)10673except ValueError:10674self.progress("PASS not able to set mode : %s disarmed" % mode)10675else:10676self.progress("Not armable mode : %s" % mode)10677self.change_mode(mode)10678self.run_cmd(10679mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10680p1=1, # ARM10681want_result=mavutil.mavlink.MAV_RESULT_FAILED,10682)10683self.progress("PASS not able to arm in mode : %s" % mode)10684if mode in self.get_position_armable_modes_list():10685self.progress("Armable mode needing Position : %s" % mode)10686self.wait_ekf_happy()10687self.change_mode(mode)10688self.arm_vehicle()10689self.wait_heartbeat()10690self.disarm_vehicle()10691self.progress("PASS arm mode : %s" % mode)10692self.progress("Not armable mode without Position : %s" % mode)10693self.wait_gps_disable()10694self.change_mode(mode)10695self.run_cmd(10696mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10697p1=1, # ARM10698want_result=mavutil.mavlink.MAV_RESULT_FAILED,10699)10700self.set_parameter("SIM_GPS1_ENABLE", 1)10701self.wait_ekf_happy() # EKF may stay unhappy for a while10702self.progress("PASS not able to arm without Position in mode : %s" % mode)10703if mode in self.get_no_position_not_settable_modes_list():10704self.progress("Setting mode need Position : %s" % mode)10705self.wait_ekf_happy()10706self.wait_gps_disable()10707try:10708self.change_mode(mode, timeout=15)10709except AutoTestTimeoutException:10710self.set_parameter("SIM_GPS1_ENABLE", 1)10711self.progress("PASS not able to set mode without Position : %s" % mode)10712except ValueError:10713self.set_parameter("SIM_GPS1_ENABLE", 1)10714self.progress("PASS not able to set mode without Position : %s" % mode)10715if mode == "FOLLOW":10716self.set_parameter("FOLL_ENABLE", 0)10717self.change_mode(self.default_mode())10718if self.armed():10719self.disarm_vehicle()1072010721# we should find at least one Armed event and one disarmed10722# event, and at least one ARM message for arm and disarm10723wants = set([10724("Armed EV message", "EV", lambda e : e.Id == 10),10725("Disarmed EV message", "EV", lambda e : e.Id == 11),10726("Armed ARM message", "ARM", lambda a : a.ArmState == 1),10727("Disarmed ARM message", "ARM", lambda a : a.ArmState == 0),10728])1072910730dfreader = self.dfreader_for_current_onboard_log()10731types = set()10732for (name, msgtype, l) in wants:10733types.add(msgtype)1073410735while True:10736m = dfreader.recv_match(type=types)10737if m is None:10738break10739wantscopy = copy.copy(wants)10740for want in wantscopy:10741(name, msgtype, l) = want10742if m.get_type() != msgtype:10743continue10744if l(m):10745self.progress("Found %s" % name)10746wants.discard(want)10747if len(wants) == 0:10748break1074910750if len(wants):10751msg = ", ".join([x[0] for x in wants])10752raise NotAchievedException("Did not find (%s)" % msg)1075310754self.progress("ALL PASS")10755# TODO : Test arming magic;1075610757def measure_message_rate(self, victim_message, timeout=10, mav=None):10758if mav is None:10759mav = self.mav10760tstart = self.get_sim_time()10761count = 010762while self.get_sim_time_cached() < tstart + timeout:10763m = mav.recv_match(10764type=victim_message,10765blocking=True,10766timeout=0.110767)10768if m is not None:10769count += 110770if mav != self.mav:10771self.drain_mav(self.mav)1077210773time_delta = self.get_sim_time_cached() - tstart10774self.progress("%s count after %f seconds: %u" %10775(victim_message, time_delta, count))10776return count/time_delta1077710778def rate_to_interval_us(self, rate):10779return 1/float(rate)*1000000.01078010781def interval_us_to_rate(self, interval):10782if interval == 0:10783raise ValueError("Zero interval is infinite rate")10784return 1000000.0/float(interval)1078510786def set_message_rate_hz(self, id, rate_hz, mav=None, run_cmd=None):10787'''set a message rate in Hz; 0 for original, -1 to disable'''10788if run_cmd is None:10789run_cmd = self.run_cmd10790if isinstance(id, str):10791id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id)10792if rate_hz == 0 or rate_hz == -1:10793set_interval = rate_hz10794else:10795set_interval = self.rate_to_interval_us(rate_hz)10796run_cmd(10797mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,10798p1=id,10799p2=set_interval,10800mav=mav,10801)1080210803def get_message_rate_hz(self, id, mav=None, run_cmd=None):10804'''return rate message is being sent, in Hz'''10805if run_cmd is None:10806run_cmd = self.run_cmd1080710808interval = self.get_message_interval(id, mav=mav, run_cmd=run_cmd)10809return self.interval_us_to_rate(interval)1081010811def send_get_message_interval(self, victim_message, mav=None):10812if mav is None:10813mav = self.mav10814if isinstance(victim_message, str):10815victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)10816mav.mav.command_long_send(108171,108181,10819mavutil.mavlink.MAV_CMD_GET_MESSAGE_INTERVAL,108201, # confirmation10821float(victim_message),108220,108230,108240,108250,108260,108270)1082810829def get_message_interval(self, victim_message, mav=None, run_cmd=None):10830'''returns message interval in microseconds'''10831if run_cmd is None:10832run_cmd = self.run_cmd1083310834self.send_get_message_interval(victim_message, mav=mav)10835m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=1, mav=mav)1083610837if isinstance(victim_message, str):10838victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)10839if m.message_id != victim_message:10840raise NotAchievedException(f"Unexpected ID in MESSAGE_INTERVAL (want={victim_message}, got={m.message_id}")1084110842return m.interval_us1084310844def set_message_interval(self, victim_message, interval_us, mav=None):10845'''sets message interval in microseconds'''10846if isinstance(victim_message, str):10847victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)10848self.run_cmd(10849mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,10850p1=victim_message,10851p2=interval_us,10852mav=mav,10853)1085410855def test_rate(self,10856desc,10857in_rate,10858expected_rate10859, mav=None,10860victim_message="VFR_HUD",10861ndigits=0,10862message_rate_sample_period=10):10863if mav is None:10864mav = self.mav1086510866self.progress("###### %s" % desc)10867self.progress("Setting rate to %f" % round(in_rate, ndigits=ndigits))1086810869self.set_message_rate_hz(victim_message, in_rate, mav=mav)1087010871new_measured_rate = self.measure_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav)10872self.progress(10873"Measured rate: %f (want %f)" %10874(round(new_measured_rate, ndigits=ndigits),10875round(expected_rate, ndigits=ndigits))10876)10877notachieved_ex = None10878if round(new_measured_rate, ndigits=ndigits) != round(expected_rate, ndigits=ndigits):10879notachieved_ex = NotAchievedException(10880"Rate not achieved (got %f want %f)" %10881(round(new_measured_rate, ndigits),10882round(expected_rate, ndigits)))1088310884# make sure get_message_interval works:10885self.send_get_message_interval(victim_message, mav=mav)1088610887m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=30, mav=mav)1088810889if in_rate == 0:10890want = self.rate_to_interval_us(expected_rate)10891elif in_rate == -1:10892want = in_rate10893else:10894want = self.rate_to_interval_us(in_rate)1089510896if m.interval_us != want:10897raise NotAchievedException("Did not read same interval back from autopilot: want=%d got=%d)" %10898(want, m.interval_us))10899m = self.assert_receive_message('COMMAND_ACK', mav=mav)10900if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:10901raise NotAchievedException("Expected ACCEPTED for reading message interval")1090210903if notachieved_ex is not None:10904raise notachieved_ex1090510906def SET_MESSAGE_INTERVAL(self):10907'''Test MAV_CMD_SET_MESSAGE_INTERVAL'''10908self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger10909self.reboot_sitl() # needed for CAM1_TYPE to take effect10910self.start_subtest('Basic tests')10911self.test_set_message_interval_basic()10912self.start_subtest('Many-message tests')10913self.test_set_message_interval_many()1091410915def MESSAGE_INTERVAL_COMMAND_INT(self):10916'''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT'''10917original_rate = round(self.measure_message_rate("VFR_HUD", 20))10918self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)10919if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1:10920raise NotAchievedException("Did not set rate")1092110922# Try setting a rate well beyond SCHED_LOOP_RATE10923self.run_cmd(10924mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,10925p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD,10926p2=self.rate_to_interval_us(800),10927want_result=mavutil.mavlink.MAV_RESULT_DENIED,10928)1092910930self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT")10931# 148 is AUTOPILOT_VERSION:10932self.context_collect('AUTOPILOT_VERSION')10933self.run_cmd_int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, 148)10934self.delay_sim_time(2)10935count = len(self.context_collection('AUTOPILOT_VERSION'))10936if count != 1:10937raise NotAchievedException(f"Did not get single AUTOPILOT_VERSION message (count={count}")1093810939def test_set_message_interval_many(self):10940messages = [10941'CAMERA_FEEDBACK',10942'RAW_IMU',10943'ATTITUDE',10944]10945ex = None10946try:10947rate = 510948for message in messages:10949self.set_message_rate_hz(message, rate)10950for message in messages:10951self.assert_message_rate_hz(message, rate)10952except Exception as e:10953self.print_exception_caught(e)10954ex = e1095510956# reset message rates to default:10957for message in messages:10958self.set_message_rate_hz(message, -1)1095910960if ex is not None:10961raise ex1096210963def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0, mav=None):10964if mav is None:10965mav = self.mav10966self.drain_mav(mav)10967rate = round(self.measure_message_rate(message, sample_period, mav=mav), ndigits=ndigits)10968self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits)))10969if rate != want_rate:10970raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate))1097110972def test_set_message_interval_basic(self):10973ex = None10974try:10975rate = round(self.measure_message_rate("VFR_HUD", 20))10976self.progress("Initial rate: %u" % rate)1097710978self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD")10979# this assumes the streamrates have not been played with:10980self.test_rate("Resetting original rate using 0-value", 0, rate)10981self.test_rate("Disabling using -1-value", -1, 0)10982self.test_rate("Resetting original rate", 0, rate)1098310984self.progress("try getting a message which is not ordinarily streamed out")10985rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))10986if rate != 0:10987raise PreconditionFailedException("Already getting CAMERA_FEEDBACK")10988self.progress("try various message rates")10989for want_rate in range(5, 14):10990self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,10991want_rate)10992self.assert_message_rate_hz('CAMERA_FEEDBACK', want_rate)1099310994self.progress("try at the main loop rate")10995# have to reset the speedup as MAVProxy can't keep up otherwise10996old_speedup = self.get_parameter("SIM_SPEEDUP")10997self.set_parameter("SIM_SPEEDUP", 1.0)10998# ArduPilot currently limits message rate to 80% of main loop rate:10999want_rate = self.get_parameter("SCHED_LOOP_RATE") * 0.811000self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,11001want_rate)11002rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))11003self.set_parameter("SIM_SPEEDUP", old_speedup)11004self.progress("Want=%f got=%f" % (want_rate, rate))11005if abs(rate - want_rate) > 2:11006raise NotAchievedException("Did not get expected rate")1100711008self.drain_mav()1100911010non_existant_id = 14511011self.send_get_message_interval(non_existant_id)11012m = self.assert_receive_message('MESSAGE_INTERVAL')11013if m.interval_us != 0:11014raise NotAchievedException("Supposed to get 0 back for unsupported stream")11015m = self.assert_receive_message('COMMAND_ACK')11016if m.result != mavutil.mavlink.MAV_RESULT_FAILED:11017raise NotAchievedException("Getting rate of unsupported message is a failure")1101811019except Exception as e:11020self.print_exception_caught(e)11021ex = e1102211023self.progress("Resetting CAMERA_FEEDBACK rate to default rate")11024self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, 0)11025self.assert_message_rate_hz('CAMERA_FEEDBACK', 0)1102611027if ex is not None:11028raise ex1102911030def send_poll_message(self, message_id, target_sysid=None, target_compid=None, quiet=False, mav=None):11031if mav is None:11032mav = self.mav11033if isinstance(message_id, str):11034message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)11035self.send_cmd(11036mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,11037p1=message_id,11038target_sysid=target_sysid,11039target_compid=target_compid,11040quiet=quiet,11041mav=mav,11042)1104311044def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None):11045if mav is None:11046mav = self.mav11047if target_sysid is None:11048target_sysid = self.sysid_thismav()11049if target_compid is None:11050target_compid = 111051if isinstance(message_id, str):11052message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)11053tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work11054self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid)11055self.run_cmd_get_ack(11056mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,11057mavutil.mavlink.MAV_RESULT_ACCEPTED,11058timeout,11059quiet=quiet,11060mav=mav,11061)11062while True:11063if self.get_sim_time_cached() - tstart > timeout:11064raise NotAchievedException("Did not receive polled message")11065m = mav.recv_match(blocking=True,11066timeout=0.1)11067if self.mav != mav:11068self.drain_mav()11069if m is None:11070continue11071if m.id != message_id:11072continue11073if (m.get_srcSystem() != target_sysid or11074m.get_srcComponent() != target_compid):11075continue11076return m1107711078def get_messages_frame(self, msg_names):11079'''try to get a "frame" of named messages - a set of messages as close11080in time as possible'''11081msgs = {}1108211083def get_msgs(mav, m):11084t = m.get_type()11085if t in msg_names:11086msgs[t] = m11087self.do_timesync_roundtrip()11088self.install_message_hook(get_msgs)11089for msg_name in msg_names:11090self.send_poll_message(msg_name)11091while True:11092self.mav.recv_match(blocking=True)11093if len(msgs.keys()) == len(msg_names):11094break1109511096self.remove_message_hook(get_msgs)1109711098return msgs1109911100def REQUEST_MESSAGE(self, timeout=60):11101'''Test MAV_CMD_REQUEST_MESSAGE'''11102self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger11103self.reboot_sitl() # needed for CAM1_TYPE to take effect11104rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 10))11105if rate != 0:11106raise PreconditionFailedException("Receiving camera feedback")11107self.poll_message("CAMERA_FEEDBACK")1110811109def clear_mission(self, mission_type, target_system=1, target_component=1):11110'''clear mision_type from autopilot. Note that this does NOT actually11111send a MISSION_CLEAR_ALL message11112'''11113if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_ALL:11114# recurse11115if not self.is_tracker() and not self.is_blimp():11116self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)11117if not self.is_blimp():11118self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)11119if not self.is_sub() and not self.is_tracker() and not self.is_blimp():11120self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)11121self.last_wp_load = time.time()11122return1112311124self.mav.mav.mission_count_send(target_system,11125target_component,111260,11127mission_type)11128self.assert_received_message_field_values('MISSION_ACK', {11129"target_system": self.mav.mav.srcSystem,11130"target_component": self.mav.mav.srcComponent,11131"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,11132})1113311134if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:11135self.last_wp_load = time.time()1113611137def clear_fence_using_mavproxy(self, mavproxy, timeout=10):11138mavproxy.send("fence clear\n")11139tstart = self.get_sim_time_cached()11140while True:11141now = self.get_sim_time_cached()11142if now - tstart > timeout:11143raise AutoTestTimeoutException("FENCE_TOTAL did not go to zero")11144if self.get_parameter("FENCE_TOTAL") == 0:11145break1114611147def clear_fence(self):11148self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1114911150# Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa11151def ConfigErrorLoop(self):11152'''test the sensor config error loop works and that parameter sets are persistent'''11153parameter_name = "SERVO8_MIN"11154old_parameter_value = self.get_parameter(parameter_name)11155old_sim_baro_count = self.get_parameter("SIM_BARO_COUNT")11156new_parameter_value = old_parameter_value + 511157ex = None11158try:11159self.set_parameter("STAT_BOOTCNT", 0)11160self.set_parameter("SIM_BARO_COUNT", -1)1116111162if self.is_tracker():11163# starts armed...11164self.progress("Disarming tracker")11165self.disarm_vehicle(force=True)1116611167self.reboot_sitl(required_bootcount=1)11168self.progress("Waiting for 'Config error'")11169# SYSTEM_TIME not sent in config error loop:11170self.wait_statustext("Config error", wallclock_timeout=True)11171self.progress("Setting %s to %f" % (parameter_name, new_parameter_value))11172self.set_parameter(parameter_name, new_parameter_value)11173except Exception as e:11174ex = e1117511176self.progress("Resetting SIM_BARO_COUNT")11177self.set_parameter("SIM_BARO_COUNT", old_sim_baro_count)1117811179if self.is_tracker():11180# starts armed...11181self.progress("Disarming tracker")11182self.disarm_vehicle(force=True)1118311184self.progress("Calling reboot-sitl ")11185self.reboot_sitl(required_bootcount=2)1118611187if ex is not None:11188raise ex1118911190if self.get_parameter(parameter_name) != new_parameter_value:11191raise NotAchievedException("Parameter value did not stick")1119211193def InitialMode(self):11194'''Test initial mode switching'''11195if self.is_copter():11196init_mode = (9, "LAND")11197if self.is_rover():11198init_mode = (4, "HOLD")11199if self.is_plane():11200init_mode = (13, "TAKEOFF")11201if self.is_tracker():11202init_mode = (1, "STOP")11203if self.is_sub():11204return # NOT Supported yet11205self.context_push()11206self.set_parameter("SIM_RC_FAIL", 1)11207self.progress("Setting INITIAL_MODE to %s" % init_mode[1])11208self.set_parameter("INITIAL_MODE", init_mode[0])11209self.reboot_sitl()11210self.wait_mode(init_mode[1])11211self.progress("Testing back mode switch")11212self.set_parameter("SIM_RC_FAIL", 0)11213self.wait_for_mode_switch_poll()11214self.context_pop()11215self.reboot_sitl()1121611217def Gripper(self):11218'''Test gripper'''11219self.GripperType(1) # servo11220self.GripperType(2) # EPM1122111222def GripperType(self, gripper_type):11223'''test specific gripper type'''11224self.context_push()11225self.set_parameters({11226"GRIP_ENABLE": 1,11227"GRIP_GRAB": 2000,11228"GRIP_RELEASE": 1000,11229"GRIP_TYPE": gripper_type,11230"SIM_GRPS_ENABLE": 1,11231"SIM_GRPS_PIN": 8,11232"SERVO8_FUNCTION": 28,11233"SERVO8_MIN": 1000,11234"SERVO8_MAX": 2000,11235"SERVO9_MIN": 1000,11236"SERVO9_MAX": 2000,11237"RC9_OPTION": 19,11238})11239self.set_rc(9, 1500)11240self.reboot_sitl()11241self.progress("Waiting for ready to arm")11242self.wait_ready_to_arm()11243self.progress("Test gripper with RC9_OPTION")11244self.progress("Releasing load")11245# non strict string matching because of catching text issue....11246self.context_collect('STATUSTEXT')11247self.set_rc(9, 1000)11248self.wait_text("Gripper load releas", check_context=True)11249self.progress("Grabbing load")11250self.set_rc(9, 2000)11251self.wait_text("Gripper load grabb", check_context=True)11252self.context_clear_collection('STATUSTEXT')11253self.progress("Releasing load")11254self.set_rc(9, 1000)11255self.wait_text("Gripper load releas", check_context=True)11256self.progress("Grabbing load")11257self.set_rc(9, 2000)11258self.wait_text("Gripper load grabb", check_context=True)11259self.progress("Test gripper with Mavlink cmd")1126011261self.context_collect('STATUSTEXT')11262self.progress("Releasing load")11263self.run_cmd(11264mavutil.mavlink.MAV_CMD_DO_GRIPPER,11265p1=1,11266p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE11267)11268self.wait_text("Gripper load releas", check_context=True)11269self.progress("Grabbing load")11270self.run_cmd(11271mavutil.mavlink.MAV_CMD_DO_GRIPPER,11272p1=1,11273p2=mavutil.mavlink.GRIPPER_ACTION_GRAB11274)11275self.wait_text("Gripper load grabb", check_context=True)1127611277self.context_clear_collection('STATUSTEXT')11278self.progress("Releasing load")11279self.run_cmd_int(11280mavutil.mavlink.MAV_CMD_DO_GRIPPER,11281p1=1,11282p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE11283)11284self.wait_text("Gripper load releas", check_context=True)1128511286self.progress("Grabbing load")11287self.run_cmd_int(11288mavutil.mavlink.MAV_CMD_DO_GRIPPER,11289p1=1,11290p2=mavutil.mavlink.GRIPPER_ACTION_GRAB11291)11292self.wait_text("Gripper load grabb", check_context=True)1129311294self.context_pop()11295self.reboot_sitl()1129611297def TestLocalHomePosition(self):11298"""Test local home position is sent in HOME_POSITION message"""11299self.context_push()11300self.wait_ready_to_arm()1130111302# set home to a new location11303self.mav.mav.command_long_send(1,113041,11305mavutil.mavlink.MAV_CMD_DO_SET_HOME,113060,113070,113080,113090,113100,11311-35.357466,11312149.142589,11313630)1131411315# check home after home set11316m = self.assert_receive_message("HOME_POSITION", timeout=5)11317if abs(m.x) < 10 or abs(m.y) < 10 or abs(m.z) < 10:11318raise NotAchievedException("Failed to get local home position: (got=%u, %u, %u)", m.x, m.y, m.z)11319else:11320self.progress("Received local home position successfully: (got=%f, %f, %f)" %11321(m.x, m.y, m.z))1132211323self.context_pop()11324self.reboot_sitl()1132511326def install_terrain_handlers_context(self):11327'''install a message handler into the current context which will11328listen for an fulfill terrain requests from ArduPilot. Will11329die if the data is not available - but11330self.terrain_in_offline_mode can be set to true in the11331constructor to change this behaviour11332'''1133311334def check_terrain_requests(mav, m):11335if m.get_type() != 'TERRAIN_REQUEST':11336return11337self.progress("Processing TERRAIN_REQUEST (%s)" %11338self.dump_message_verbose(m))11339# swiped from mav_terrain.py11340for bit in range(56):11341if m.mask & (1 << bit) == 0:11342continue1134311344lat = m.lat * 1.0e-711345lon = m.lon * 1.0e-711346bit_spacing = m.grid_spacing * 411347(lat, lon) = mp_util.gps_offset(lat, lon,11348east=bit_spacing * (bit % 8),11349north=bit_spacing * (bit // 8))11350data = []11351for i in range(4*4):11352y = i % 411353x = i // 411354(lat2, lon2) = mp_util.gps_offset(lat, lon,11355east=m.grid_spacing * y,11356north=m.grid_spacing * x)11357# if we are in online mode then we'll try to fetch11358# from the internet into the cache dir:11359for i in range(120):11360alt = self.elevationmodel.GetElevation(lat2, lon2)11361if alt is not None:11362break11363if self.terrain_in_offline_mode:11364break11365self.progress("No elevation data for (%f %f); retry" %11366(lat2, lon2))11367time.sleep(1)11368if alt is None:11369# no data - we can't send the packet11370raise ValueError("No elevation data for (%f %f)" % (lat2, lon2))11371data.append(int(alt))11372self.terrain_data_messages_sent += 111373self.mav.mav.terrain_data_send(m.lat,11374m.lon,11375m.grid_spacing,11376bit,11377data)1137811379self.install_message_hook_context(check_terrain_requests)1138011381def install_messageprinter_handlers_context(self, messages):11382'''monitor incoming messages, print them out'''11383def check_messages(mav, m):11384if m.get_type() not in messages:11385return11386self.progress(self.dump_message_verbose(m))1138711388self.install_message_hook_context(check_messages)1138911390def SetpointGlobalPos(self, timeout=100):11391"""Test set position message in guided mode."""11392# Disable heading and yaw test on rover type1139311394if self.is_rover():11395test_alt = True11396test_heading = False11397test_yaw_rate = False11398else:11399test_alt = True11400test_heading = True11401test_yaw_rate = True1140211403self.install_terrain_handlers_context()1140411405self.set_parameter("FS_GCS_ENABLE", 0)11406self.change_mode("GUIDED")11407self.wait_ready_to_arm()11408self.arm_vehicle()1140911410if self.is_copter() or self.is_heli():11411self.user_takeoff(alt_min=50)1141211413targetpos = self.mav.location()11414wp_accuracy = None11415if self.is_copter() or self.is_heli():11416wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)11417wp_accuracy = wp_accuracy * 0.01 # cm to m11418if self.is_plane() or self.is_rover():11419wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)11420if wp_accuracy is None:11421raise ValueError()1142211423def to_alt_frame(alt, mav_frame):11424if mav_frame in ["MAV_FRAME_GLOBAL_RELATIVE_ALT",11425"MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",11426"MAV_FRAME_GLOBAL_TERRAIN_ALT",11427"MAV_FRAME_GLOBAL_TERRAIN_ALT_INT"]:11428home = self.home_position_as_mav_location()11429return alt - home.alt11430else:11431return alt1143211433def send_target_position(lat, lng, alt, mav_frame):11434self.mav.mav.set_position_target_global_int_send(114350, # timestamp11436self.sysid_thismav(), # target system_id114371, # target component id11438mav_frame,11439MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11440MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11441MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11442MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11443int(lat * 1.0e7), # lat11444int(lng * 1.0e7), # lon11445alt, # alt114460, # vx114470, # vy114480, # vz114490, # afx114500, # afy114510, # afz114520, # yaw114530, # yawrate11454)1145511456def testpos(self, targetpos : mavutil.location, test_alt : bool, frame_name : str, frame):11457send_target_position(targetpos.lat, targetpos.lng, to_alt_frame(targetpos.alt, frame_name), frame)11458self.wait_location(11459targetpos,11460accuracy=wp_accuracy,11461timeout=timeout,11462height_accuracy=(2 if test_alt else None),11463minimum_duration=2,11464)1146511466for frame in MAV_FRAMES_TO_TEST:11467frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name11468self.start_subtest("Testing Set Position in %s" % frame_name)11469self.start_subtest("Changing Latitude")11470targetpos.lat += 0.000111471if test_alt:11472targetpos.alt += 511473testpos(self, targetpos, test_alt, frame_name, frame)1147411475self.start_subtest("Changing Longitude")11476targetpos.lng += 0.000111477if test_alt:11478targetpos.alt -= 511479testpos(self, targetpos, test_alt, frame_name, frame)1148011481self.start_subtest("Revert Latitude")11482targetpos.lat -= 0.000111483if test_alt:11484targetpos.alt += 511485testpos(self, targetpos, test_alt, frame_name, frame)1148611487self.start_subtest("Revert Longitude")11488targetpos.lng -= 0.000111489if test_alt:11490targetpos.alt -= 511491testpos(self, targetpos, test_alt, frame_name, frame)1149211493if test_heading:11494self.start_subtest("Testing Yaw targetting in %s" % frame_name)11495self.progress("Changing Latitude and Heading")11496targetpos.lat += 0.000111497if test_alt:11498targetpos.alt += 511499self.mav.mav.set_position_target_global_int_send(115000, # timestamp11501self.sysid_thismav(), # target system_id115021, # target component id11503frame,11504MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11505MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11506MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11507int(targetpos.lat * 1.0e7), # lat11508int(targetpos.lng * 1.0e7), # lon11509to_alt_frame(targetpos.alt, frame_name), # alt115100, # vx115110, # vy115120, # vz115130, # afx115140, # afy115150, # afz11516math.radians(42), # yaw115170, # yawrate11518)11519self.wait_location(11520targetpos,11521accuracy=wp_accuracy,11522timeout=timeout,11523height_accuracy=(2 if test_alt else None),11524minimum_duration=2,11525)11526self.wait_heading(42, minimum_duration=5, timeout=timeout)1152711528self.start_subtest("Revert Latitude and Heading")11529targetpos.lat -= 0.000111530if test_alt:11531targetpos.alt -= 511532self.mav.mav.set_position_target_global_int_send(115330, # timestamp11534self.sysid_thismav(), # target system_id115351, # target component id11536frame,11537MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11538MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11539MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11540int(targetpos.lat * 1.0e7), # lat11541int(targetpos.lng * 1.0e7), # lon11542to_alt_frame(targetpos.alt, frame_name), # alt115430, # vx115440, # vy115450, # vz115460, # afx115470, # afy115480, # afz11549math.radians(0), # yaw115500, # yawrate11551)11552self.wait_location(11553targetpos,11554accuracy=wp_accuracy,11555timeout=timeout,11556height_accuracy=(2 if test_alt else None),11557minimum_duration=2,11558)11559self.wait_heading(0, minimum_duration=5, timeout=timeout)1156011561if test_yaw_rate:11562self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)1156311564def send_yaw_rate(rate, target=None):11565self.mav.mav.set_position_target_global_int_send(115660, # timestamp11567self.sysid_thismav(), # target system_id115681, # target component id11569frame,11570MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11571MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11572MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,11573int(targetpos.lat * 1.0e7), # lat11574int(targetpos.lng * 1.0e7), # lon11575to_alt_frame(targetpos.alt, frame_name), # alt115760, # vx115770, # vy115780, # vz115790, # afx115800, # afy115810, # afz115820, # yaw11583rate, # yawrate in rad/s11584)1158511586self.start_subtest("Changing Latitude and Yaw rate")11587target_rate = 1.0 # in rad/s11588targetpos.lat += 0.000111589if test_alt:11590targetpos.alt += 511591self.wait_yaw_speed(target_rate, timeout=timeout,11592called_function=lambda plop, empty: send_yaw_rate(11593target_rate, None), minimum_duration=5)11594self.wait_location(11595targetpos,11596accuracy=wp_accuracy,11597timeout=timeout,11598height_accuracy=(2 if test_alt else None),11599)1160011601self.start_subtest("Revert Latitude and invert Yaw rate")11602target_rate = -1.011603targetpos.lat -= 0.000111604if test_alt:11605targetpos.alt -= 511606self.wait_yaw_speed(target_rate, timeout=timeout,11607called_function=lambda plop, empty: send_yaw_rate(11608target_rate, None), minimum_duration=5)11609self.wait_location(11610targetpos,11611accuracy=wp_accuracy,11612timeout=timeout,11613height_accuracy=(2 if test_alt else None),11614)11615self.start_subtest("Changing Yaw rate to zero")11616target_rate = 0.011617self.wait_yaw_speed(target_rate, timeout=timeout,11618called_function=lambda plop, empty: send_yaw_rate(11619target_rate, None), minimum_duration=5)1162011621self.progress("Getting back to home and disarm")11622self.do_RTL(distance_min=0, distance_max=wp_accuracy)11623self.disarm_vehicle()1162411625def SetpointBadVel(self, timeout=30):11626'''try feeding in a very, very bad velocity and make sure it is ignored'''11627self.takeoff(mode='GUIDED')11628# following values from a real log:11629target_speed = Vector3(-3.6019095525029597e+30,116301.7796490496925177e-41,116313.0557017120313744e-26)1163211633self.progress("Feeding in bad global data, hoping we don't move")1163411635def send_speed_vector_global_int(vector , mav_frame):11636self.mav.mav.set_position_target_global_int_send(116370, # timestamp11638self.sysid_thismav(), # target system_id116391, # target component id11640mav_frame,11641MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11642MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11643MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11644MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,116450,116460,116470,11648vector.x, # vx11649vector.y, # vy11650vector.z, # vz116510, # afx116520, # afy116530, # afz116540, # yaw116550, # yawrate11656)11657self.wait_speed_vector(11658Vector3(0, 0, 0),11659timeout=timeout,11660called_function=lambda plop, empty: send_speed_vector_global_int(target_speed, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT), # noqa11661minimum_duration=1011662)1166311664self.progress("Feeding in bad local data, hoping we don't move")1166511666def send_speed_vector_local_ned(vector , mav_frame):11667self.mav.mav.set_position_target_local_ned_send(116680, # timestamp11669self.sysid_thismav(), # target system_id116701, # target component id11671mav_frame,11672MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11673MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11674MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11675MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,116760,116770,116780,11679vector.x, # vx11680vector.y, # vy11681vector.z, # vz116820, # afx116830, # afy116840, # afz116850, # yaw116860, # yawrate11687)11688self.wait_speed_vector(11689Vector3(0, 0, 0),11690timeout=timeout,11691called_function=lambda plop, empty: send_speed_vector_local_ned(target_speed, mavutil.mavlink.MAV_FRAME_LOCAL_NED), # noqa11692minimum_duration=1011693)1169411695self.do_RTL()1169611697def SetpointGlobalVel(self, timeout=30):11698"""Test set position message in guided mode."""11699# Disable heading and yaw rate test on rover type11700if self.is_rover():11701test_vz = False11702test_heading = False11703test_yaw_rate = False11704else:11705test_vz = True11706test_heading = True11707test_yaw_rate = True1170811709self.install_terrain_handlers_context()1171011711self.set_parameter("FS_GCS_ENABLE", 0)11712self.change_mode("GUIDED")11713self.wait_ready_to_arm()11714self.arm_vehicle()1171511716if self.is_copter() or self.is_heli():11717self.user_takeoff(alt_min=50)1171811719target_speed = Vector3(1.0, 0.0, 0.0)1172011721wp_accuracy = None11722if self.is_copter() or self.is_heli():11723wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)11724wp_accuracy = wp_accuracy * 0.01 # cm to m11725if self.is_plane() or self.is_rover():11726wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)11727if wp_accuracy is None:11728raise ValueError()1172911730def send_speed_vector(vector, mav_frame):11731self.mav.mav.set_position_target_global_int_send(117320, # timestamp11733self.sysid_thismav(), # target system_id117341, # target component id11735mav_frame,11736MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11737MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11738MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11739MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,117400,117410,117420,11743vector.x, # vx11744vector.y, # vy11745vector.z, # vz117460, # afx117470, # afy117480, # afz117490, # yaw117500, # yawrate11751)1175211753for frame in MAV_FRAMES_TO_TEST:11754frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name11755self.start_subtest("Testing Set Velocity in %s" % frame_name)11756self.progress("Changing Vx speed")11757self.wait_speed_vector(11758target_speed,11759timeout=timeout,11760called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11761minimum_duration=211762)1176311764self.start_subtest("Add Vy speed")11765target_speed.y = 1.011766self.wait_speed_vector(11767target_speed,11768timeout=timeout,11769called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11770minimum_duration=2)1177111772self.start_subtest("Add Vz speed")11773if test_vz:11774target_speed.z = 1.011775else:11776target_speed.z = 0.011777self.wait_speed_vector(11778target_speed,11779timeout=timeout,11780called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11781minimum_duration=211782)1178311784self.start_subtest("Invert Vz speed")11785if test_vz:11786target_speed.z = -1.011787else:11788target_speed.z = 0.011789self.wait_speed_vector(11790target_speed,11791timeout=timeout,11792called_function=lambda plop, empty: send_speed_vector(target_speed, frame), minimum_duration=211793)1179411795self.start_subtest("Invert Vx speed")11796target_speed.x = -1.011797self.wait_speed_vector(11798target_speed,11799timeout=timeout,11800called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11801minimum_duration=211802)1180311804self.start_subtest("Invert Vy speed")11805target_speed.y = -1.011806self.wait_speed_vector(11807target_speed,11808timeout=timeout,11809called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11810minimum_duration=211811)1181211813self.start_subtest("Set Speed to zero")11814target_speed.x = 0.011815target_speed.y = 0.011816target_speed.z = 0.011817self.wait_speed_vector(11818target_speed,11819timeout=timeout,11820called_function=lambda plop, empty: send_speed_vector(target_speed, frame),11821minimum_duration=211822)1182311824if test_heading:11825self.start_subtest("Testing Yaw targetting in %s" % frame_name)1182611827def send_yaw_target(yaw, mav_frame):11828self.mav.mav.set_position_target_global_int_send(118290, # timestamp11830self.sysid_thismav(), # target system_id118311, # target component id11832mav_frame,11833MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11834MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11835MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,118360,118370,118380,118390, # vx118400, # vy118410, # vz118420, # afx118430, # afy118440, # afz11845math.radians(yaw), # yaw118460, # yawrate11847)1184811849target_speed.x = 1.011850target_speed.y = 1.011851if test_vz:11852target_speed.z = -1.011853else:11854target_speed.z = 0.01185511856def send_yaw_target_vel(yaw, vector, mav_frame):11857self.mav.mav.set_position_target_global_int_send(118580, # timestamp11859self.sysid_thismav(), # target system_id118601, # target component id11861mav_frame,11862MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11863MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11864MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,118650,118660,118670,11868vector.x, # vx11869vector.y, # vy11870vector.z, # vz118710, # afx118720, # afy118730, # afz11874math.radians(yaw), # yaw118750, # yawrate11876)1187711878self.start_subtest("Target a fixed Heading")11879target_yaw = 42.011880self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,11881called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))1188211883self.start_subtest("Set target Heading")11884target_yaw = 0.011885self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,11886called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))1188711888self.start_subtest("Add Vx, Vy, Vz speed and target a fixed Heading")11889target_yaw = 42.011890self.wait_heading(11891target_yaw,11892minimum_duration=5,11893timeout=timeout,11894called_function=lambda p, e: send_yaw_target_vel(target_yaw,11895target_speed,11896frame)11897)11898self.wait_speed_vector(11899target_speed,11900called_function=lambda p, e: send_yaw_target_vel(target_yaw,11901target_speed,11902frame)11903)1190411905self.start_subtest("Stop Vx, Vy, Vz speed and target zero Heading")11906target_yaw = 0.011907target_speed.x = 0.011908target_speed.y = 0.011909target_speed.z = 0.011910self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,11911called_function=lambda plop, empty: send_yaw_target_vel(target_yaw, target_speed, frame))11912self.wait_speed_vector(11913target_speed,11914timeout=timeout,11915called_function=lambda p, ee: send_yaw_target_vel(target_yaw,11916target_speed,11917frame),11918minimum_duration=211919)1192011921if test_yaw_rate:11922self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)1192311924def send_yaw_rate(rate, mav_frame):11925self.mav.mav.set_position_target_global_int_send(119260, # timestamp11927self.sysid_thismav(), # target system_id119281, # target component id11929mav_frame,11930MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11931MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11932MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,119330,119340,119350,119360, # vx119370, # vy119380, # vz119390, # afx119400, # afy119410, # afz119420, # yaw11943rate, # yawrate in rad/s11944)1194511946target_speed.x = 1.011947target_speed.y = 1.011948if test_vz:11949target_speed.z = -1.011950else:11951target_speed.z = 0.01195211953def send_yaw_rate_vel(rate, vector, mav_frame):11954self.mav.mav.set_position_target_global_int_send(119550, # timestamp11956self.sysid_thismav(), # target system_id119571, # target component id11958mav_frame,11959MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11960MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11961MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,119620,119630,119640,11965vector.x, # vx11966vector.y, # vy11967vector.z, # vz119680, # afx119690, # afy119700, # afz119710, # yaw11972rate, # yawrate in rad/s11973)1197411975self.start_subtest("Set Yaw rate")11976target_rate = 1.011977self.wait_yaw_speed(target_rate, timeout=timeout,11978called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1197911980self.start_subtest("Invert Yaw rate")11981target_rate = -1.011982self.wait_yaw_speed(target_rate, timeout=timeout,11983called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1198411985self.start_subtest("Stop Yaw rate")11986target_rate = 0.011987self.wait_yaw_speed(target_rate, timeout=timeout,11988called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1198911990self.start_subtest("Set Yaw Rate and Vx, Vy, Vz speed")11991target_rate = 1.011992self.wait_yaw_speed(11993target_rate,11994called_function=lambda p, e: send_yaw_rate_vel(target_rate,11995target_speed,11996frame),11997minimum_duration=211998)11999self.wait_speed_vector(12000target_speed,12001timeout=timeout,12002called_function=lambda p, e: send_yaw_rate_vel(target_rate,12003target_speed,12004frame),12005minimum_duration=212006)1200712008target_rate = -1.012009target_speed.x = -1.012010target_speed.y = -1.012011if test_vz:12012target_speed.z = 1.012013else:12014target_speed.z = 0.012015self.start_subtest("Invert Vx, Vy, Vz speed")12016self.wait_yaw_speed(12017target_rate,12018timeout=timeout,12019called_function=lambda p, e: send_yaw_rate_vel(target_rate,12020target_speed,12021frame),12022minimum_duration=212023)12024self.wait_speed_vector(12025target_speed,12026timeout=timeout,12027called_function=lambda p, e: send_yaw_rate_vel(target_rate,12028target_speed,12029frame),12030minimum_duration=212031)1203212033target_rate = 0.012034target_speed.x = 0.012035target_speed.y = 0.012036target_speed.z = 0.012037self.start_subtest("Stop Yaw rate and all speed")12038self.wait_yaw_speed(12039target_rate,12040timeout=timeout,12041called_function=lambda p, e: send_yaw_rate_vel(target_rate,12042target_speed,12043frame),12044minimum_duration=212045)12046self.wait_speed_vector(12047target_speed,12048timeout=timeout,12049called_function=lambda p, e: send_yaw_rate_vel(target_rate,12050target_speed,12051frame),12052minimum_duration=212053)1205412055self.progress("Getting back to home and disarm")12056self.do_RTL(distance_min=0, distance_max=wp_accuracy)12057self.disarm_vehicle()1205812059def is_blimp(self):12060return False1206112062def is_copter(self):12063return False1206412065def is_sub(self):12066return False1206712068def is_plane(self):12069return False1207012071def is_rover(self):12072return False1207312074def is_balancebot(self):12075return False1207612077def is_heli(self):12078return False1207912080def is_tracker(self):12081return False1208212083def initial_mode(self):12084'''return mode vehicle should start in with no RC inputs set'''12085return None1208612087def initial_mode_switch_mode(self):12088'''return mode vehicle should start in with default RC inputs set'''12089return None1209012091def upload_fences_from_locations(self, fences, target_system=1, target_component=1):12092seq = 012093items = []1209412095for (vertex_type, locs) in fences:12096if isinstance(locs, dict):12097# circular fence12098item = self.mav.mav.mission_item_int_encode(12099target_system,12100target_component,12101seq, # seq12102mavutil.mavlink.MAV_FRAME_GLOBAL,12103vertex_type,121040, # current121050, # autocontinue12106locs["radius"], # p1121070, # p2121080, # p3121090, # p412110int(locs["loc"].lat * 1e7), # latitude12111int(locs["loc"].lng * 1e7), # longitude1211233.0000, # altitude12113mavutil.mavlink.MAV_MISSION_TYPE_FENCE)12114seq += 112115items.append(item)12116continue12117count = len(locs)12118for loc in locs:12119item = self.mav.mav.mission_item_int_encode(12120target_system,12121target_component,12122seq, # seq12123mavutil.mavlink.MAV_FRAME_GLOBAL,12124vertex_type,121250, # current121260, # autocontinue12127count, # p1121280, # p2121290, # p3121300, # p412131int(loc.lat * 1e7), # latitude12132int(loc.lng * 1e7), # longitude1213333.0000, # altitude12134mavutil.mavlink.MAV_MISSION_TYPE_FENCE)12135seq += 112136items.append(item)1213712138self.check_fence_upload_download(items)1213912140def rally_MISSION_ITEM_INT_from_loc(self, loc):12141return self.create_MISSION_ITEM_INT(12142mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,12143x=int(loc.lat*1e7),12144y=int(loc.lng*1e7),12145z=loc.alt,12146frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,12147mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY12148)1214912150def upload_rally_points_from_locations(self, rally_point_locs):12151'''takes a sequence of locations, sets vehicle rally points to those locations'''12152items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs]12153self.correct_wp_seq_numbers(items)12154self.check_rally_upload_download(items)1215512156def wait_for_initial_mode(self):12157'''wait until we get a heartbeat with an expected initial mode (the12158one specified in the vehicle constructor)'''12159want = self.initial_mode()12160if want is None:12161return12162self.progress("Waiting for initial mode %s" % want)12163self.wait_mode(want)1216412165def wait_for_mode_switch_poll(self):12166'''look for a transition from boot-up-mode (e.g. the flightmode12167specificied in Copter's constructor) to the one specified by the mode12168switch value'''12169want = self.initial_mode_switch_mode()12170if want is None:12171return12172self.progress("Waiting for mode-switch mode %s" % want)12173self.wait_mode(want)1217412175def start_subtest(self, description):12176self.progress("-")12177self.progress("---------- %s ----------" % description)12178self.progress("-")1217912180def start_subsubtest(self, description):12181self.progress(".")12182self.progress(".......... %s .........." % description)12183self.progress(".")1218412185def end_subtest(self, description):12186'''TODO: sanity checks?'''12187pass1218812189def end_subsubtest(self, description):12190'''TODO: sanity checks?'''12191pass1219212193def last_onboard_log(self):12194'''return number of last onboard log'''12195mavproxy = self.start_mavproxy()12196mavproxy.send("module load log\n")12197loaded_module = False12198mavproxy.expect(["Loaded module log", "module log already loaded"])12199if mavproxy.match.group(0) == "Loaded module log":12200loaded_module = True12201mavproxy.send("log list\n")12202mavproxy.expect(["lastLog ([0-9]+)", "No logs"])12203if mavproxy.match.group(0) == "No logs":12204num_log = None12205else:12206num_log = int(mavproxy.match.group(1))12207if loaded_module:12208mavproxy.send("module unload log\n")12209mavproxy.expect("Unloaded module log")12210self.stop_mavproxy(mavproxy)12211return num_log1221212213def current_onboard_log_number(self):12214logs = self.download_full_log_list(print_logs=False)12215return sorted(logs.keys())[-1]1221612217def current_onboard_log_filepath(self):12218'''return filepath to currently open dataflash log. We assume that's12219the latest log...'''12220logs = self.log_list()12221latest = logs[-1]12222return latest1222312224def dfreader_for_path(self, path):12225return DFReader.DFReader_binary(path,12226zero_time_base=True)1222712228def dfreader_for_current_onboard_log(self):12229return self.dfreader_for_path(self.current_onboard_log_filepath())1223012231def current_onboard_log_contains_message(self, messagetype):12232self.progress("Checking (%s) for (%s)" %12233(self.current_onboard_log_filepath(), messagetype))12234dfreader = self.dfreader_for_current_onboard_log()12235m = dfreader.recv_match(type=messagetype)12236print("m=%s" % str(m))12237return m is not None1223812239def assert_current_onboard_log_contains_message(self, messagetype):12240if not self.current_onboard_log_contains_message(messagetype):12241raise NotAchievedException("Current onboard log does not contain message %s" % messagetype)1224212243def run_tests(self, tests) -> List[Result]:12244"""Autotest vehicle in SITL."""12245if self.run_tests_called:12246raise ValueError("run_tests called twice")12247self.run_tests_called = True1224812249result_list = []1225012251try:12252self.init()1225312254self.progress("Waiting for a heartbeat with mavlink protocol %s"12255% self.mav.WIRE_PROTOCOL_VERSION)12256self.wait_heartbeat()12257self.wait_for_initial_mode()12258self.progress("Setting up RC parameters")12259self.set_rc_default()12260self.wait_for_mode_switch_poll()12261if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling12262self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)1226312264for test in tests:12265self.drain_mav_unparsed()12266result_list.append(self.run_one_test(test))1226712268except pexpect.TIMEOUT:12269self.progress("Failed with timeout")12270result = Result(test)12271result.passed = False12272result.reason = "Failed with timeout"12273result_list.append(result)12274if self.logs_dir:12275if glob.glob("core*") or glob.glob("ap-*.core"):12276self.check_logs("FRAMEWORK")1227712278if self.rc_thread is not None:12279self.progress("Joining RC thread")12280self.rc_thread_should_quit = True12281self.rc_thread.join()12282self.rc_thread = None1228312284if self.mav is not None:12285self.mav.close()12286self.mav = None1228712288self.stop_SITL()1228912290valgrind_log = util.valgrind_log_filepath(binary=self.binary,12291model=self.frame)12292files = glob.glob("*" + valgrind_log)12293valgrind_failed = False12294for valgrind_log in files:12295os.chmod(valgrind_log, 0o644)12296if os.path.getsize(valgrind_log) > 0:12297target = self.buildlogs_path("%s-%s" % (12298self.log_name(),12299os.path.basename(valgrind_log)))12300self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target))12301shutil.move(valgrind_log, target)12302valgrind_failed = True12303if valgrind_failed:12304result_list.append(ValgrindFailedResult())1230512306return result_list1230712308def dictdiff(self, dict1, dict2):12309fred = copy.copy(dict1)12310for key in dict2.keys():12311try:12312del fred[key]12313except KeyError:12314pass12315return fred1231612317# download parameters tries to cope with its download being12318# interrupted or broken by simply retrying the download a few12319# times.12320def download_parameters(self, target_system, target_component):12321# try a simple fetch-all:12322last_parameter_received = 012323attempt_count = 012324start_done = False12325# make flake8 happy:12326count = 012327expected_count = 012328seen_ids = {}12329self.progress("Downloading parameters")12330debug = False12331while True:12332now = self.get_sim_time_cached()12333if not start_done or now - last_parameter_received > 10:12334start_done = True12335if attempt_count > 3:12336raise AutoTestTimeoutException("Failed to download parameters (have %s/%s) (seen_ids-count=%u)" %12337(str(count), str(expected_count), len(seen_ids.keys())))12338elif attempt_count != 0:12339self.progress("Download failed; retrying")12340self.delay_sim_time(1)12341debug = True12342self.drain_mav()12343self.mav.mav.param_request_list_send(target_system, target_component)12344attempt_count += 112345count = 012346expected_count = None12347seen_ids = {}12348id_seq = {}12349m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=10)12350if m is None:12351raise AutoTestTimeoutException("tardy PARAM_VALUE (have %s/%s)" % (12352str(count), str(expected_count)))12353if m.param_index == 65535:12354self.progress("volunteered parameter: %s" % str(m))12355continue12356if debug:12357self.progress(" received id=%4u param_count=%4u %s=%f" %12358(m.param_index, m.param_count, m.param_id, m.param_value))12359if m.param_index >= m.param_count:12360raise ValueError("parameter index (%u) gte parameter count (%u)" %12361(m.param_index, m.param_count))12362if expected_count is None:12363expected_count = m.param_count12364else:12365if m.param_count != expected_count:12366raise ValueError("expected count changed")12367if m.param_id not in seen_ids:12368count += 112369seen_ids[m.param_id] = m.param_value12370last_parameter_received = now12371if count == expected_count:12372break1237312374self.progress("Downloaded %u parameters OK (attempt=%u)" %12375(count, attempt_count))12376return (seen_ids, id_seq)1237712378def test_parameters_download(self):12379self.start_subtest("parameter download")12380target_system = self.sysid_thismav()12381target_component = 112382self.progress("First Download:")12383(parameters, seq_id) = self.download_parameters(target_system, target_component)12384self.reboot_sitl()12385self.progress("Second download:")12386(parameters2, seq2_id) = self.download_parameters(target_system, target_component)1238712388delta = self.dictdiff(parameters, parameters2)12389if len(delta) != 0:12390raise ValueError("Got %u fewer parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %12391(len(delta), len(parameters), len(parameters2), str(delta.keys())))1239212393delta = self.dictdiff(parameters2, parameters)12394if len(delta) != 0:12395raise ValueError("Got %u extra parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %12396(len(delta), len(parameters), len(parameters2), str(delta.keys())))1239712398self.end_subsubtest("parameter download")1239912400def test_enable_parameter(self):12401self.start_subtest("enable parameters")12402target_system = 112403target_component = 112404parameters = self.download_parameters(target_system, target_component)12405enable_parameter = self.sample_enable_parameter()12406if enable_parameter is None:12407self.progress("Skipping enable parameter check as no enable parameter supplied")12408return12409self.set_parameter(enable_parameter, 1)12410parameters2 = self.download_parameters(target_system, target_component)12411if len(parameters) == len(parameters2):12412raise NotAchievedException("Enable parameter did not increase no of parameters downloaded")12413self.end_subsubtest("enable download")1241412415def test_parameters_mis_total(self):12416self.start_subsubtest("parameter mis_total")12417if self.is_tracker():12418# uses CMD_TOTAL not MIS_TOTAL, and it's in a scalr not a12419# group and it's generally all bad.12420return12421self.start_subtest("Ensure GCS is not able to set MIS_TOTAL")12422old_mt = self.get_parameter("MIS_TOTAL", attempts=20) # retries to avoid seeming race condition with MAVProxy12423ex = None12424try:12425self.set_parameter("MIS_TOTAL", 17, attempts=1)12426except ValueError as e:12427ex = e12428if ex is None:12429raise NotAchievedException("Set parameter when I shouldn't have")12430if old_mt != self.get_parameter("MIS_TOTAL"):12431raise NotAchievedException("Total has changed")1243212433self.start_subtest("Ensure GCS is able to set other MIS_ parameters")12434self.set_parameter("MIS_OPTIONS", 1)12435if self.get_parameter("MIS_OPTIONS") != 1:12436raise NotAchievedException("Failed to set MIS_OPTIONS")1243712438mavproxy = self.start_mavproxy()12439from_mavproxy = self.get_parameter_mavproxy(mavproxy, "MIS_OPTIONS")12440if from_mavproxy != 1:12441raise NotAchievedException("MAVProxy failed to get parameter")12442self.stop_mavproxy(mavproxy)1244312444def test_parameter_documentation(self):12445'''ensure parameter documentation is valid'''12446self.start_subsubtest("Check all parameters are documented")12447self.test_parameter_documentation_get_all_parameters()1244812449def Parameters(self):12450'''general small tests for parameter system'''12451if self.is_balancebot():12452# same binary and parameters as Rover12453return12454self.test_parameter_documentation()12455self.test_parameters_mis_total()12456self.test_parameters_download()1245712458def disabled_tests(self):12459return {}1246012461def test_parameter_checks_poscontrol(self, param_prefix):12462self.wait_ready_to_arm()12463self.context_push()12464self.set_parameter("%s_POSXY_P" % param_prefix, -1)12465self.run_cmd(12466mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,12467p1=1, # ARM12468timeout=4,12469want_result=mavutil.mavlink.MAV_RESULT_FAILED,12470)12471self.context_pop()12472self.run_cmd(12473mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,12474p1=1, # ARM12475timeout=4,12476want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,12477)12478self.disarm_vehicle()1247912480def assert_not_receiving_message(self, message, timeout=1, mav=None):12481self.progress("making sure we're not getting %s messages" % message)12482if mav is None:12483mav = self.mav12484m = mav.recv_match(type=message, blocking=True, timeout=timeout)12485if m is not None:12486raise PreconditionFailedException("Receiving %s messags" % message)1248712488def PIDTuning(self):12489'''Test PID Tuning'''12490self.assert_not_receiving_message('PID_TUNING', timeout=5)12491self.set_parameter("GCS_PID_MASK", 1)12492self.progress("making sure we are now getting PID_TUNING messages")12493self.assert_receive_message('PID_TUNING', timeout=5)1249412495def sample_mission_filename(self):12496return "flaps.txt"1249712498def AdvancedFailsafe(self):12499'''Test Advanced Failsafe'''12500ex = None12501try:12502self.drain_mav()12503if self.is_plane(): # other vehicles can always terminate12504self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)12505self.set_parameters({12506"AFS_ENABLE": 1,12507"SYSID_MYGCS": self.mav.source_system,12508})12509self.drain_mav()12510self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)12511self.set_parameter("AFS_TERM_ACTION", 42)12512self.load_sample_mission()12513self.context_collect("STATUSTEXT")12514self.change_mode("AUTO") # must go to auto for AFS to latch on12515self.wait_statustext("AFS State: AFS_AUTO", check_context=True)12516if self.is_plane():12517self.change_mode("MANUAL")12518elif self.is_copter():12519self.change_mode("STABILIZE")1252012521self.start_subtest("RC Failure")12522self.context_push()12523self.context_collect("STATUSTEXT")12524self.set_parameters({12525"AFS_RC_FAIL_TIME": 1,12526"SIM_RC_FAIL": 1,12527})12528self.wait_statustext("Terminating due to RC failure", check_context=True)12529self.context_pop()12530self.set_parameter("AFS_TERMINATE", 0)1253112532if not self.is_plane():12533# plane requires a polygon fence...12534self.start_subtest("Altitude Limit breach")12535self.set_parameters({12536"AFS_AMSL_LIMIT": 100,12537"AFS_QNH_PRESSURE": 1015.2,12538})12539self.do_fence_enable()12540self.wait_statustext("Terminating due to fence breach", check_context=True)12541self.set_parameter("AFS_AMSL_LIMIT", 0)12542self.set_parameter("AFS_TERMINATE", 0)12543self.do_fence_disable()1254412545self.start_subtest("GPS Failure")12546self.context_push()12547self.context_collect("STATUSTEXT")12548self.set_parameters({12549"AFS_MAX_GPS_LOSS": 1,12550"SIM_GPS1_ENABLE": 0,12551})12552self.wait_statustext("AFS State: GPS_LOSS", check_context=True)12553self.context_pop()12554self.set_parameter("AFS_TERMINATE", 0)1255512556self.start_subtest("GCS Request")12557self.context_push()12558self.context_collect("STATUSTEXT")12559self.run_cmd(12560mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,12561p1=1, # terminate12562)12563self.wait_statustext("Terminating due to GCS request", check_context=True)12564self.context_pop()12565self.set_parameter("AFS_TERMINATE", 0)1256612567except Exception as e:12568ex = e12569try:12570self.do_fence_disable()12571except ValueError:12572# may not actually be enabled....12573pass12574if ex is not None:12575raise ex1257612577def drain_mav_seconds(self, seconds):12578tstart = self.get_sim_time_cached()12579while self.get_sim_time_cached() - tstart < seconds:12580self.drain_mav()12581self.delay_sim_time(0.5)1258212583def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT", verbose=False):12584tstart = self.get_sim_time()12585while True:12586now = self.get_sim_time_cached()12587if now - tstart > timeout:12588raise AutoTestTimeoutException("Did not get good GPS lock")12589m = self.mav.recv_match(type=message_type, blocking=True, timeout=0.1)12590if verbose:12591self.progress("Received: %s" % str(m))12592if m is None:12593continue12594if m.fix_type >= fix_type:12595break1259612597def NMEAOutput(self):12598'''Test AHRS NMEA Output can be read by out NMEA GPS'''12599self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output12600self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA12601port = self.spare_network_port()12602self.customise_SITL_commandline([12603"--serial4=tcp:%u" % port, # GPS2 is NMEA....12604"--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port12605])12606self.do_timesync_roundtrip()12607self.wait_gps_fix_type_gte(3)12608gps1 = self.mav.recv_match(type="GPS_RAW_INT", blocking=True, timeout=10)12609self.progress("gps1=(%s)" % str(gps1))12610if gps1 is None:12611raise NotAchievedException("Did not receive GPS_RAW_INT")12612tstart = self.get_sim_time()12613while True:12614now = self.get_sim_time_cached()12615if now - tstart > 20:12616raise NotAchievedException("NMEA output not updating?!")12617gps2 = self.mav.recv_match(type="GPS2_RAW", blocking=True, timeout=1)12618self.progress("gps2=%s" % str(gps2))12619if gps2 is None:12620continue12621if gps2.time_usec != 0:12622break12623max_distance = 112624distance = self.get_distance_int(gps1, gps2)12625if distance > max_distance:12626raise NotAchievedException("NMEA output inaccurate (dist=%f want<%f)" %12627(distance, max_distance))1262812629def mavproxy_load_module(self, mavproxy, module):12630mavproxy.send("module load %s\n" % module)12631mavproxy.expect("Loaded module %s" % module)1263212633def mavproxy_unload_module(self, mavproxy, module):12634mavproxy.send("module unload %s\n" % module)12635mavproxy.expect("Unloaded module %s" % module)1263612637def AccelCal(self):12638'''Accelerometer Calibration testing'''12639ex = None12640mavproxy = self.start_mavproxy()12641try:12642# setup with pre-existing accel offsets, to show that existing offsets don't12643# adversely affect a new cal12644pre_aofs = [Vector3(2.8, 1.2, 1.7),12645Vector3(0.2, -0.9, 2.9)]12646pre_ascale = [Vector3(0.95, 1.2, 0.98),12647Vector3(1.1, 1.0, 0.93)]12648aofs = [Vector3(0.7, -0.3, 1.8),12649Vector3(-2.1, 1.9, 2.3)]12650ascale = [Vector3(0.98, 1.12, 1.05),12651Vector3(1.11, 0.98, 0.96)]12652atrim = Vector3(0.05, -0.03, 0)12653pre_atrim = Vector3(-0.02, 0.04, 0)12654param_map = [("INS_ACCOFFS", "SIM_ACC1_BIAS", pre_aofs[0], aofs[0]),12655("INS_ACC2OFFS", "SIM_ACC2_BIAS", pre_aofs[1], aofs[1]),12656("INS_ACCSCAL", "SIM_ACC1_SCAL", pre_ascale[0], ascale[0]),12657("INS_ACC2SCAL", "SIM_ACC2_SCAL", pre_ascale[1], ascale[1]),12658("AHRS_TRIM", "SIM_ACC_TRIM", pre_atrim, atrim)]12659axes = ['X', 'Y', 'Z']1266012661# form the pre-calibration params12662initial_params = {}12663for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:12664for axis in axes:12665initial_params[ins_prefix + "_" + axis] = getattr(pre_value, axis.lower())12666initial_params[sim_prefix + "_" + axis] = getattr(post_value, axis.lower())12667self.set_parameters(initial_params)12668self.customise_SITL_commandline(["-M", "calibration"])12669self.mavproxy_load_module(mavproxy, "sitl_calibration")12670self.mavproxy_load_module(mavproxy, "calibration")12671self.mavproxy_load_module(mavproxy, "relay")12672mavproxy.send("sitl_accelcal\n")12673mavproxy.send("accelcal\n")12674mavproxy.expect("Calibrated")12675for wanted in [12676"level",12677"on its LEFT side",12678"on its RIGHT side",12679"nose DOWN",12680"nose UP",12681"on its BACK",12682]:12683timeout = 212684mavproxy.expect("Place vehicle %s and press any key." % wanted, timeout=timeout)12685mavproxy.expect("sitl_accelcal: sending attitude, please wait..", timeout=timeout)12686mavproxy.expect("sitl_accelcal: attitude detected, please press any key..", timeout=timeout)12687mavproxy.send("\n")12688mavproxy.expect(".*Calibration successful", timeout=timeout)12689self.drain_mav()1269012691self.progress("Checking results")12692accuracy_pct = 0.512693for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:12694for axis in axes:12695pname = ins_prefix+"_"+axis12696v = self.get_parameter(pname)12697expected_v = getattr(post_value, axis.lower())12698if v == expected_v:12699continue12700error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)12701if error_pct > accuracy_pct:12702raise NotAchievedException(12703"Incorrect value %.6f for %s should be %.6f error %.2f%%" %12704(v, pname, expected_v, error_pct))12705else:12706self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct))12707except Exception as e:12708self.print_exception_caught(e)12709ex = e12710self.mavproxy_unload_module(mavproxy, "relay")12711self.mavproxy_unload_module(mavproxy, "calibration")12712self.mavproxy_unload_module(mavproxy, "sitl_calibration")12713self.stop_mavproxy(mavproxy)12714if ex is not None:12715raise ex1271612717def ahrstrim_preflight_cal(self):12718# setup with non-zero accel offsets12719self.set_parameters({12720"INS_ACCOFFS_X": 0.7,12721"INS_ACCOFFS_Y": -0.3,12722"INS_ACCOFFS_Z": 1.8,12723"INS_ACC2OFFS_X": -2.1,12724"INS_ACC2OFFS_Y": 1.9,12725"INS_ACC2OFFS_Z": 2.3,12726"SIM_ACC1_BIAS_X": 0.7,12727"SIM_ACC1_BIAS_Y": -0.3,12728"SIM_ACC1_BIAS_Z": 1.8,12729"SIM_ACC2_BIAS_X": -2.1,12730"SIM_ACC2_BIAS_Y": 1.9,12731"SIM_ACC2_BIAS_Z": 2.3,12732"AHRS_TRIM_X": 0.05,12733"AHRS_TRIM_Y": -0.03,12734"SIM_ACC_TRIM_X": -0.04,12735"SIM_ACC_TRIM_Y": 0.05,12736})12737expected_parms = {12738"AHRS_TRIM_X": -0.04,12739"AHRS_TRIM_Y": 0.05,12740}1274112742self.progress("Starting ahrstrim")12743self.drain_mav()12744self.mav.mav.command_long_send(self.sysid_thismav(), 1,12745mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,127460, 0, 0, 0, 2, 0, 0)12747self.wait_statustext('Trim OK')12748self.drain_mav()1274912750self.progress("Checking results")12751accuracy_pct = 0.212752for (pname, expected_v) in expected_parms.items():12753v = self.get_parameter(pname)12754if v == expected_v:12755continue12756error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)12757if error_pct > accuracy_pct:12758raise NotAchievedException(12759"Incorrect value %.6f for %s should be %.6f error %.2f%%" %12760(v, pname, expected_v, error_pct))12761self.progress("Correct value %.4f for %s error %.2f%%" %12762(v, pname, error_pct))1276312764def user_takeoff(self, alt_min=30, timeout=30, max_err=5):12765'''takeoff using mavlink takeoff command'''12766self.run_cmd(12767mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,12768p7=alt_min, # param712769)12770self.wait_altitude(alt_min - 1,12771(alt_min + max_err),12772relative=True,12773timeout=timeout)1277412775def ahrstrim_attitude_correctness(self):12776self.wait_ready_to_arm()12777HOME = self.sitl_start_location()12778for heading in 0, 90:12779self.customise_SITL_commandline([12780"--home", "%s,%s,%s,%s" % (HOME.lat, HOME.lng, HOME.alt, heading)12781])12782for ahrs_type in [0, 2, 3]:12783self.start_subsubtest("Testing AHRS_TYPE=%u" % ahrs_type)12784self.context_push()12785self.set_parameter("AHRS_EKF_TYPE", ahrs_type)12786self.reboot_sitl()12787self.wait_prearm_sys_status_healthy()12788for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:12789self.set_parameters({12790'AHRS_TRIM_X': math.radians(r),12791'AHRS_TRIM_Y': math.radians(p),12792"SIM_ACC_TRIM_X": math.radians(r),12793"SIM_ACC_TRIM_Y": math.radians(p),12794})12795self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5)12796if ahrs_type != 0: # we don't get secondary msgs while DCM is primary12797self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)12798self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)1279912800self.context_pop()12801self.reboot_sitl()1280212803def AHRSTrim(self):12804'''AHRS trim testing'''12805self.start_subtest("Attitude Correctness")12806self.ahrstrim_attitude_correctness()12807self.delay_sim_time(5)12808self.start_subtest("Preflight Calibration")12809self.ahrstrim_preflight_cal()1281012811def Button(self):12812'''Test Buttons'''12813self.set_parameter("SIM_PIN_MASK", 0)12814self.set_parameter("BTN_ENABLE", 1)12815self.drain_mav()12816self.do_heartbeats(force=True)12817btn = 412818pin = 312819self.set_parameter("BTN_PIN%u" % btn, pin, verbose=True)12820m = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=1)12821self.progress("### m: %s" % str(m))12822if m is not None:12823# should not get a button-changed event here. The pins12824# are simulated pull-down12825raise NotAchievedException("Received BUTTON_CHANGE event")12826mask = 1 << pin12827self.set_parameter("SIM_PIN_MASK", mask)12828m = self.assert_receive_message('BUTTON_CHANGE', timeout=1, verbose=True)12829if not (m.state & mask):12830raise NotAchievedException("Bit not set in mask (got=%u want=%u)" % (m.state, mask))12831m2 = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=10)12832if m2 is None:12833raise NotAchievedException("Did not get repeat message")12834self.progress("### m2: %s" % str(m2))12835# wait for messages to stop coming:12836self.drain_mav_seconds(15)1283712838new_mask = 012839self.send_set_parameter("SIM_PIN_MASK", new_mask, verbose=True)12840m3 = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=1)12841if m3 is None:12842raise NotAchievedException("Did not get 'off' message")12843self.progress("### m3: %s" % str(m3))1284412845if m.last_change_ms == m3.last_change_ms:12846raise NotAchievedException("last_change_ms same as first message")12847if m3.state != new_mask:12848raise NotAchievedException("Unexpected mask (want=%u got=%u)" %12849(new_mask, m3.state))12850self.progress("correct BUTTON_CHANGE event received")1285112852if self.is_tracker():12853# tracker starts armed, which is annoying12854self.progress("Skipping arm/disarm tests for tracker")12855return1285612857self.context_push()12858self.wait_ready_to_arm()12859self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM12860self.set_parameter("SIM_PIN_MASK", mask)12861self.wait_armed()12862self.set_parameter("SIM_PIN_MASK", 0)12863self.wait_disarmed()12864self.context_pop()1286512866if self.is_rover():12867self.context_push()12868# arming should be inhibited while e-STOP is in use:12869# set the function:12870self.set_parameter("BTN_FUNC%u" % btn, 31)12871# invert the sense of the pin, so eStop is asserted when pin is low:12872self.set_parameter("BTN_OPTIONS%u" % btn, 1 << 1)12873self.reboot_sitl()12874# assert the pin:12875self.set_parameter("SIM_PIN_MASK", mask)12876self.wait_ready_to_arm()12877self.arm_vehicle()12878self.disarm_vehicle()12879# de-assert the pin:12880self.set_parameter("SIM_PIN_MASK", 0)12881self.delay_sim_time(1) # 5Hz update rate on Button library12882self.context_collect("STATUSTEXT")12883# try to arm the vehicle:12884self.run_cmd(12885mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,12886p1=1, # ARM12887want_result=mavutil.mavlink.MAV_RESULT_FAILED,12888)12889self.assert_prearm_failure("Motors Emergency Stopped",12890other_prearm_failures_fatal=False)12891self.reboot_sitl()12892self.assert_prearm_failure(12893"Motors Emergency Stopped",12894other_prearm_failures_fatal=False)12895self.context_pop()12896self.reboot_sitl()1289712898if self.is_rover():12899self.start_subtest("Testing using buttons for changing modes")12900self.context_push()12901if not self.mode_is('MANUAL'):12902raise NotAchievedException("Bad mode")12903self.set_parameter("BTN_FUNC%u" % btn, 53) # steering mode12904# press button:12905self.set_parameter("SIM_PIN_MASK", mask)12906self.wait_mode('STEERING')12907# release button:12908self.set_parameter("SIM_PIN_MASK", 0)12909self.wait_mode('MANUAL')12910self.context_pop()1291112912def compare_number_percent(self, num1, num2, percent):12913if num1 == 0 and num2 == 0:12914return True12915if abs(num1 - num2) / max(abs(num1), abs(num2)) <= percent * 0.01:12916return True12917return False1291812919def bit_extract(self, number, offset, length):12920mask = 012921for i in range(offset, offset+length):12922mask |= 1 << i12923return (number & mask) >> offset1292412925def tf_encode_gps_latitude(self, lat):12926value = 012927if lat < 0:12928value = ((abs(lat)//100)*6) | 0x4000000012929else:12930value = ((abs(lat)//100)*6)12931return value1293212933def tf_validate_gps(self, value): # shared by proto 4 and proto 1012934self.progress("validating gps (0x%02x)" % value)12935lat = value12936gpi = self.mav.recv_match(12937type='GLOBAL_POSITION_INT',12938blocking=True,12939timeout=112940)12941if gpi is None:12942raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")12943gpi_lat = self.tf_encode_gps_latitude(gpi.lat)12944self.progress("GLOBAL_POSITION_INT lat==%f frsky==%f" % (gpi_lat, lat))12945if gpi_lat == lat:12946return True12947return False1294812949def tfp_prep_number(self, number, digits, power):12950res = 012951abs_number = abs(number)12952if digits == 2 and power == 1: # number encoded on 8 bits: 7 bits for digits + 1 for 10^power12953if abs_number < 100:12954res = abs_number << 112955elif abs_number < 1270:12956res = (round(abs_number * 0.1) << 1) | 0x112957else: # transmit max possible value (0x7F x 10^1 = 1270)12958res = 0xFF12959if number < 0: # if number is negative, add sign bit in front12960res |= 0x1 << 812961elif digits == 2 and power == 2: # number encoded on 9 bits: 7 bits for digits + 2 for 10^power12962if abs_number < 100:12963res = abs_number << 212964elif abs_number < 1000:12965res = (round(abs_number * 0.1) << 2) | 0x112966elif abs_number < 10000:12967res = (round(abs_number * 0.01) << 2) | 0x212968elif abs_number < 127000:12969res = (round(abs_number * 0.001) << 2) | 0x312970else: # transmit max possible value (0x7F x 10^3 = 127000)12971res = 0x1FF12972if number < 0: # if number is negative, add sign bit in front12973res |= 0x1 << 912974elif digits == 3 and power == 1: # number encoded on 11 bits: 10 bits for digits + 1 for 10^power12975if abs_number < 1000:12976res = abs_number << 112977elif abs_number < 10240:12978res = (round(abs_number * 0.1) << 1) | 0x112979else: # transmit max possible value (0x3FF x 10^1 = 10240)12980res = 0x7FF12981if number < 0: # if number is negative, add sign bit in front12982res |= 0x1 << 1112983elif digits == 3 and power == 2: # number encoded on 12 bits: 10 bits for digits + 2 for 10^power12984if abs_number < 1000:12985res = abs_number << 212986elif abs_number < 10000:12987res = (round(abs_number * 0.1) << 2) | 0x112988elif abs_number < 100000:12989res = (round(abs_number * 0.01) << 2) | 0x212990elif abs_number < 1024000:12991res = (round(abs_number * 0.001) << 2) | 0x312992else: # transmit max possible value (0x3FF x 10^3 = 127000)12993res = 0xFFF12994if number < 0: # if number is negative, add sign bit in front12995res |= 0x1 << 1212996return res1299712998def tfp_validate_ap_status(self, value): # 0x500112999self.progress("validating ap_status(0x%02x)" % value)13000flight_mode = self.bit_extract(value, 0, 5) - 1 # first mode is 1 not 0 :-)13001# simple_mode = self.bit_extract(value, 5, 2)13002# is_flying = not self.bit_extract(value, 7, 1)13003# status_armed = self.bit_extract(value, 8, 1)13004# batt_failsafe = self.bit_extract(value, 9, 1)13005# ekf_failsafe = self.bit_extract(value, 10, 2)13006# imu_temp = self.bit_extract(value, 26, 6) + 19 # IMU temperature: 0 means temp =< 19, 63 means temp => 8213007heartbeat = self.wait_heartbeat()13008mav_flight_mode = heartbeat.custom_mode13009self.progress(" mode=%u heartbeat=%u" % (flight_mode, mav_flight_mode))13010if mav_flight_mode == flight_mode:13011self.progress("flight mode match")13012return True13013# FIXME: need to check other values as well13014return False1301513016def tfp_validate_attitude(self, value):13017self.progress("validating attitude(0x%02x)" % value)13018roll = (min(self.bit_extract(value, 0, 11), 1800) - 900) * 0.2 # roll [0,1800] ==> [-180,180]13019pitch = (min(self.bit_extract(value, 11, 10), 900) - 450) * 0.2 # pitch [0,900] ==> [-90,90]13020# rng_cm = self.bit_extract(value, 22, 10) * (10 ^ self.bit_extract(value, 21, 1)) # cm13021atti = self.mav.recv_match(13022type='ATTITUDE',13023blocking=True,13024timeout=113025)13026if atti is None:13027raise NotAchievedException("Did not get ATTITUDE message")13028atti_roll = round(atti.roll)13029self.progress("ATTITUDE roll==%f frsky==%f" % (atti_roll, roll))13030if abs(atti_roll - roll) >= 5:13031return False13032atti_pitch = round(atti.pitch)13033self.progress("ATTITUDE pitch==%f frsky==%f" % (atti_pitch, pitch))13034if abs(atti_pitch - pitch) >= 5:13035return False13036# FIXME: need to check other values as well13037return True1303813039def tfp_validate_home_status(self, value):13040self.progress("validating home status(0x%02x)" % value)13041# home_dist_m = self.bit_extract(value,2,10) * (10^self.bit_extract(value,0,2))13042home_alt_dm = self.bit_extract(value, 14, 10) * (10 ^ self.bit_extract(value, 12, 2)) * 0.1 * (self.bit_extract(value, 24, 1) == 1 and -1 or 1) # noqa13043# home_angle_d = self.bit_extract(value, 25, 7) * 313044gpi = self.mav.recv_match(13045type='GLOBAL_POSITION_INT',13046blocking=True,13047timeout=113048)13049if gpi is None:13050raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")13051gpi_relative_alt_dm = gpi.relative_alt/100.013052self.progress("GLOBAL_POSITION_INT rel_alt==%fm frsky_home_alt==%fm" % (gpi_relative_alt_dm, home_alt_dm))13053if abs(gpi_relative_alt_dm - home_alt_dm) < 10:13054return True13055# FIXME: need to check other values as well13056return False1305713058def tfp_validate_gps_status(self, value):13059self.progress("validating gps status(0x%02x)" % value)13060# num_sats = self.bit_extract(value, 0, 4)13061gps_status = self.bit_extract(value, 4, 2) + self.bit_extract(value, 14, 2)13062# gps_hdop = self.bit_extract(value, 7, 7) * (10 ^ self.bit_extract(value, 6, 1)) # dm13063# gps_alt = self.bit_extract(value, 24, 7) * (10 ^ self.bit_extract(value, 22, 2)) * (self.bit_extract(value, 31, 1) == 1 and -1 or 1) # dm # noqa13064gri = self.mav.recv_match(13065type='GPS_RAW_INT',13066blocking=True,13067timeout=113068)13069if gri is None:13070raise NotAchievedException("Did not get GPS_RAW_INT message")13071gri_status = gri.fix_type13072self.progress("GPS_RAW_INT fix_type==%f frsky==%f" % (gri_status, gps_status))13073if gps_status == gri_status:13074return True13075# FIXME: need to check other values as well13076return False1307713078def tfp_validate_vel_and_yaw(self, value): # 0x500513079self.progress("validating vel_and_yaw(0x%02x)" % value)13080z_vel_dm_per_second = self.bit_extract(value, 1, 7) * (10 ^ self.bit_extract(value, 0, 1)) * (self.bit_extract(value, 8, 1) == 1 and -1 or 1) # noqa13081xy_vel = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))13082yaw = self.bit_extract(value, 17, 11) * 0.213083gpi = self.mav.recv_match(13084type='GLOBAL_POSITION_INT',13085blocking=True,13086timeout=113087)13088if gpi is None:13089return13090self.progress(" yaw=%u gpi=%u" % (yaw, gpi.hdg*0.01))13091self.progress(" xy_vel=%u" % xy_vel)13092self.progress(" z_vel_dm_per_second=%u" % z_vel_dm_per_second)13093if self.compare_number_percent(gpi.hdg*0.01, yaw, 10):13094self.progress("Yaw match")13095return True13096# FIXME: need to be under way to check the velocities, really....13097return False1309813099def tfp_validate_battery1(self, value):13100self.progress("validating battery1 (0x%02x)" % value)13101voltage = self.bit_extract(value, 0, 9) # dV13102# current = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))13103# mah = self.bit_extract(value, 17, 15)13104voltage = value * 0.113105batt = self.mav.recv_match(13106type='BATTERY_STATUS',13107blocking=True,13108timeout=5,13109condition="BATTERY_STATUS.id==0"13110)13111if batt is None:13112raise NotAchievedException("Did not get BATTERY_STATUS message")13113battery_status_value = batt.voltages[0]*0.00113114self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_value, voltage))13115if abs(battery_status_value - voltage) > 0.1:13116return False13117# FIXME: need to check other values as well13118return True1311913120def tfp_validate_params(self, value):13121param_id = self.bit_extract(value, 24, 4)13122param_value = self.bit_extract(value, 0, 24)13123self.progress("received param (0x%02x) (id=%u value=%u)" %13124(value, param_id, param_value))13125frame_type = param_value13126hb = self.mav.messages['HEARTBEAT']13127hb_type = hb.type13128self.progress("validate_params: HEARTBEAT type==%f frsky==%f param_id=%u" % (hb_type, frame_type, param_id))13129if param_id != 1:13130return False13131if hb_type == frame_type:13132return True13133# FIXME: need to check other values as well13134return False1313513136def tfp_validate_rpm(self, value):13137self.progress("validating rpm (0x%02x)" % value)13138tf_rpm = self.bit_extract(value, 0, 16)13139rpm = self.mav.recv_match(13140type='RPM',13141blocking=True,13142timeout=513143)13144if rpm is None:13145raise NotAchievedException("Did not get RPM message")13146rpm_value = round(rpm.rpm1 * 0.1)13147self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tf_rpm))13148if rpm_value != tf_rpm:13149return False13150return True1315113152def tfp_validate_terrain(self, value):13153self.progress("validating terrain(0x%02x)" % value)13154alt_above_terrain_dm = self.bit_extract(value, 2, 10) * (10 ^ self.bit_extract(value, 0, 2)) * 0.1 * (self.bit_extract(value, 12, 1) == 1 and -1 or 1) # noqa13155terrain = self.mav.recv_match(13156type='TERRAIN_REPORT',13157blocking=True,13158timeout=113159)13160if terrain is None:13161raise NotAchievedException("Did not get TERRAIN_REPORT message")13162altitude_terrain_dm = round(terrain.current_height*10)13163self.progress("TERRAIN_REPORT terrain_alt==%fdm frsky_terrain_alt==%fdm" % (altitude_terrain_dm, alt_above_terrain_dm))13164if abs(altitude_terrain_dm - alt_above_terrain_dm) < 1:13165return True13166return False1316713168def tfp_validate_wind(self, value):13169self.progress("validating wind(0x%02x)" % value)13170speed_m = self.bit_extract(value, 8, 7) * (10 ^ self.bit_extract(value, 7, 1)) * 0.1 # speed in m/s13171wind = self.mav.recv_match(13172type='WIND',13173blocking=True,13174timeout=113175)13176if wind is None:13177raise NotAchievedException("Did not get WIND message")13178self.progress("WIND mav==%f frsky==%f" % (speed_m, wind.speed))13179if abs(speed_m - wind.speed) < 0.5:13180return True13181return False1318213183def test_frsky_passthrough_do_wants(self, frsky, wants):1318413185tstart = self.get_sim_time_cached()13186while len(wants):13187self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))13188wants_copy = copy.copy(wants)13189self.drain_mav()13190t2 = self.get_sim_time_cached()13191if t2 - tstart > 300:13192self.progress("Failed to get frsky passthrough data")13193self.progress("Counts of sensor_id polls sent:")13194frsky.dump_sensor_id_poll_counts_as_progress_messages()13195self.progress("Counts of dataids received:")13196frsky.dump_dataid_counts_as_progress_messages()13197raise AutoTestTimeoutException("Failed to get frsky passthrough data")13198frsky.update()13199for want in wants_copy:13200data = frsky.get_data(want)13201if data is None:13202continue13203self.progress("Checking 0x%x" % (want,))13204if wants[want](data):13205self.progress(" Fulfilled")13206del wants[want]1320713208def FRSkyPassThroughStatustext(self):13209'''test FRSKy protocol's telem-passthrough functionality'''13210# we disable terrain here as RCTelemetry can queue a lot of13211# statustexts if terrain tiles aren't available which can13212# happen on the autotest server.13213self.set_parameters({13214"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough13215"RPM1_TYPE": 10, # enable RPM output13216"TERRAIN_ENABLE": 0,13217})13218port = self.spare_network_port()13219self.customise_SITL_commandline([13220"--serial5=tcp:%u" % port # serial5 spews to localhost port13221])13222frsky = FRSkyPassThrough(("127.0.0.1", port),13223get_time=self.get_sim_time_cached)1322413225# waiting until we are ready to arm should ensure our wanted13226# statustext doesn't get blatted out of the ArduPilot queue by13227# random messages.13228self.wait_ready_to_arm()1322913230# test we get statustext strings. This relies on ArduPilot13231# emitting statustext strings when we fetch parameters. (or,13232# now, an updating-barometer statustext)13233tstart = self.get_sim_time()13234old_data = None13235text = ""1323613237self.context_collect('STATUSTEXT')13238command = mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION13239self.send_cmd(13240command,13241p3=1, # p3, baro13242)13243# this is a test for asynchronous handling of mavlink messages:13244self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_IN_PROGRESS, 2)13245self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_ACCEPTED, 5)1324613247received_frsky_texts = []13248last_len_received_statustexts = 013249timeout = 7 * self.speedup # it can take a *long* time to get these messages down!13250while True:13251self.drain_mav()13252now = self.get_sim_time_cached()13253if now - tstart > timeout:13254raise NotAchievedException("Did not get statustext in time")13255frsky.update()13256data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats.13257if data is None:13258continue13259# frsky sends each quartet three times; skip the suplicates.13260if old_data is not None and old_data == data:13261continue13262old_data = data13263self.progress("Got (0x%x)" % data)13264severity = 013265last = False13266for i in 3, 2, 1, 0:13267x = (data >> i*8) & 0xff13268text += chr(x & 0x7f)13269self.progress(" x=0x%02x" % x)13270if x & 0x80:13271severity += 1 << i13272self.progress("Text sev=%u: %s" % (severity, str(text)))13273if (x & 0x7f) == 0x00:13274last = True13275if last:13276m = None13277text = text.rstrip("\0")13278self.progress("Received frsky text (%s)" % (text,))13279self.progress("context texts: %s" %13280str([st.text for st in self.context_collection('STATUSTEXT')]))13281m = self.statustext_in_collections(text)13282if m is not None:13283want_sev = m.severity13284if severity != want_sev:13285raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))13286self.progress("Got statustext (%s)" % m.text)13287break13288received_frsky_texts.append((severity, text))13289text = ""13290received_statustexts = self.context_collection('STATUSTEXT')13291if len(received_statustexts) != last_len_received_statustexts:13292last_len_received_statustexts = len(received_statustexts)13293self.progress("received statustexts: %s" % str([st.text for st in received_statustexts]))13294self.progress("received frsky texts: %s" % str(received_frsky_texts))13295for (want_sev, received_text) in received_frsky_texts:13296for m in received_statustexts:13297if m.text == received_text:13298if want_sev != m.severity:13299raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))13300self.progress("Got statustext (%s)" % received_text)13301break1330213303def FRSkyPassThroughSensorIDs(self):13304'''test FRSKy protocol's telem-passthrough functionality (sensor IDs)'''13305self.set_parameters({13306"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough13307"RPM1_TYPE": 10, # enable RPM output13308})13309port = self.spare_network_port()13310self.customise_SITL_commandline([13311"--serial5=tcp:%u" % port # serial5 spews to localhost port13312])13313frsky = FRSkyPassThrough(("127.0.0.1", port),13314get_time=self.get_sim_time_cached)1331513316self.wait_ready_to_arm()1331713318# we need to start the engine to get some RPM readings, we do it for plane only13319# anything with a lambda in here needs a proper test written.13320# This, at least makes sure we're getting some of each13321# message. These are ordered according to the wfq scheduler13322wants = {133230x5000: lambda xx: True,133240x5006: self.tfp_validate_attitude,133250x0800: self.tf_validate_gps,133260x5005: self.tfp_validate_vel_and_yaw,133270x5001: self.tfp_validate_ap_status,133280x5002: self.tfp_validate_gps_status,133290x5004: self.tfp_validate_home_status,13330# 0x5008: lambda x : True, # no second battery, so this doesn't arrive133310x5003: self.tfp_validate_battery1,133320x5007: self.tfp_validate_params,133330x500B: self.tfp_validate_terrain,133340x500C: self.tfp_validate_wind,13335}13336self.test_frsky_passthrough_do_wants(frsky, wants)1333713338# now check RPM:13339if self.is_plane():13340self.set_autodisarm_delay(0)13341if not self.arm_vehicle():13342raise NotAchievedException("Failed to ARM")13343self.set_rc(3, 1050)13344wants = {133450x500A: self.tfp_validate_rpm,13346}13347self.test_frsky_passthrough_do_wants(frsky, wants)13348self.zero_throttle()13349self.progress("Wait for vehicle to slow down")13350self.wait_groundspeed(0, 0.3)13351self.disarm_vehicle()1335213353self.progress("Counts of sensor_id polls sent:")13354frsky.dump_sensor_id_poll_counts_as_progress_messages()13355self.progress("Counts of dataids received:")13356frsky.dump_dataid_counts_as_progress_messages()1335713358def decode_mavlite_param_value(self, message):13359'''returns a tuple of parameter name, value'''13360(value,) = struct.unpack("<f", message[0:4])13361name = message[4:]13362return (name, value)1336313364def decode_mavlite_command_ack(self, message):13365'''returns a tuple of parameter name, value'''13366(command, result) = struct.unpack("<HB", message)13367return (command, result)1336813369def read_message_via_mavlite(self, frsky, sport_to_mavlite):13370'''read bytes from frsky mavlite stream, trying to form up a mavlite13371message'''13372tstart = self.get_sim_time()13373timeout = 30 * self.speedup/10.013374if self.valgrind or self.callgrind:13375timeout *= 1013376while True:13377self.drain_mav(quiet=True)13378tnow = self.get_sim_time_cached()13379if tnow - tstart > timeout:13380raise NotAchievedException("Did not get parameter via mavlite")13381frsky.update()13382if sport_to_mavlite.state == sport_to_mavlite.state_MESSAGE_RECEIVED:13383message = sport_to_mavlite.get_message()13384sport_to_mavlite.reset()13385# self.progress("############ message received (type=%u)" % message.msgid)13386return message1338713388def read_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):13389tstart = self.get_sim_time()13390while True:13391tnow = self.get_sim_time_cached()13392if tnow - tstart > 30 * self.speedup / 10.0:13393raise NotAchievedException("Did not get parameter via mavlite")13394message = self.read_message_via_mavlite(frsky, sport_to_mavlite)13395if message.msgid != mavutil.mavlink.MAVLINK_MSG_ID_PARAM_VALUE:13396raise NotAchievedException("Unexpected msgid %u received" % message.msgid)13397(got_name, value) = self.decode_mavlite_param_value(message.body)13398# self.progress("Received parameter: %s=%f" % (name, value))13399got_name = got_name.decode('ascii')13400if got_name != name:13401raise NotAchievedException("Incorrect name received (want=%s) (got=%s)" % (name, got_name))13402return value1340313404def get_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):13405# self.progress("########## Sending request")13406frsky.send_mavlite_param_request_read(name)13407return self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)1340813409def set_parameter_via_mavlite(self, frsky, sport_to_mavlite, name, value):13410# self.progress("########## Sending request")13411frsky.send_mavlite_param_set(name, value)13412# new value is echoed back immediately:13413got_val = self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)13414if abs(got_val - value) > 0.00001:13415raise NotAchievedException("Returned value not same as set value (want=%f got=%f)" % (value, got_val))1341613417def run_cmd_via_mavlite(self,13418frsky,13419sport_to_mavlite,13420command,13421p1=None,13422p2=None,13423p3=None,13424p4=None,13425p5=None,13426p6=None,13427p7=None,13428want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):13429frsky.send_mavlite_command_long(13430command,13431p1=p1,13432p2=p2,13433p3=p3,13434p4=p4,13435p5=p5,13436p6=p6,13437p7=p7,13438)13439self.run_cmd_via_mavlite_get_ack(13440frsky,13441sport_to_mavlite,13442command,13443want_result13444)1344513446def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_result):13447'''expect and read a command-ack from frsky sport passthrough'''13448msg = self.read_message_via_mavlite(frsky, sport_to_mavlite)13449if msg.msgid != mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_ACK:13450raise NotAchievedException("Expected a command-ack, got a %u" % msg.msgid)13451(got_command, got_result) = self.decode_mavlite_command_ack(msg.body)13452if got_command != command:13453raise NotAchievedException(13454"Did not receive expected command in command_ack; want=%u got=%u" %13455(command, got_command))13456if got_result != want_result:13457raise NotAchievedException(13458"Did not receive expected result in command_ack; want=%u got=%u" %13459(want_result, got_result))1346013461def FRSkyMAVlite(self):13462'''Test FrSky MAVlite serial output'''13463self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough13464port = self.spare_network_port()13465self.customise_SITL_commandline([13466"--serial5=tcp:%u" % port # serial5 spews to localhost port13467])13468frsky = FRSkyPassThrough(("127.0.0.1", port))13469frsky.connect()1347013471sport_to_mavlite = SPortToMAVlite()13472frsky.data_downlink_handler = sport_to_mavlite.downlink_handler1347313474self.start_subtest("Get parameter via MAVlite")13475param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles13476set_value = 97.2113477self.set_parameter(param_name, set_value) # DO NOT FLY13478got_value = self.get_parameter_via_mavlite(frsky,13479sport_to_mavlite,13480param_name)13481if abs(got_value - set_value) > 0.00001:13482raise NotAchievedException("Incorrect value retrieved via mavlite (want=%f got=%f)" % (set_value, got_value))13483self.progress("Got value OK")13484self.end_subtest("Get parameter via MAVlite")1348513486self.start_subtest("Set parameter via MAVlite")13487param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles13488set_value = 91.6713489# frsky.verbose = True13490self.set_parameter_via_mavlite(frsky, sport_to_mavlite, param_name, set_value) # DO NOT FLY13491got_value = self.get_parameter(param_name)13492if abs(got_value - set_value) > 0.00001:13493raise NotAchievedException("Incorrect value retrieved via mavlink (want=%f got=%f)" % (set_value, got_value))13494self.progress("Set value OK")13495self.end_subtest("Set parameter via MAVlite")1349613497self.start_subtest("Calibrate Baro via MAVLite")13498self.context_push()13499self.context_collect("STATUSTEXT")13500self.run_cmd_via_mavlite(13501frsky,13502sport_to_mavlite,13503mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,13504p1=0,13505p2=0,13506p3=1.0,13507)13508self.wait_statustext("Updating barometer calibration", check_context=True)13509self.context_pop()13510self.end_subtest("Calibrate Baro via MAVLite")1351113512self.start_subtest("Change mode via MAVLite")13513# FIXME: currently plane-specific13514self.run_cmd_via_mavlite(13515frsky,13516sport_to_mavlite,13517mavutil.mavlink.MAV_CMD_DO_SET_MODE,13518p1=mavutil.mavlink.PLANE_MODE_MANUAL,13519)13520self.wait_mode("MANUAL")13521self.run_cmd_via_mavlite(13522frsky,13523sport_to_mavlite,13524mavutil.mavlink.MAV_CMD_DO_SET_MODE,13525p1=mavutil.mavlink.PLANE_MODE_FLY_BY_WIRE_A,13526)13527self.wait_mode("FBWA")13528self.end_subtest("Change mode via MAVLite")1352913530self.start_subtest("Enable fence via MAVlite")13531# Fence can be enabled using MAV_CMD13532self.run_cmd_via_mavlite(13533frsky,13534sport_to_mavlite,13535mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,13536p1=1,13537want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,13538)13539self.end_subtest("Enable fence via MAVlite")1354013541def tfs_validate_gps_alt(self, value):13542self.progress("validating gps altitude (0x%02x)" % value)13543alt_m = value * 0.01 # cm -> m13544gpi = self.mav.recv_match(13545type='GLOBAL_POSITION_INT',13546blocking=True,13547timeout=113548)13549if gpi is None:13550raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")13551gpi_alt_m = round(gpi.alt * 0.001) # mm-> m13552self.progress("GLOBAL_POSITION_INT alt==%f frsky==%f" % (gpi_alt_m, alt_m))13553if self.compare_number_percent(gpi_alt_m, alt_m, 10):13554return True13555return False1355613557def tfs_validate_baro_alt(self, value):13558self.progress("validating baro altitude (0x%02x)" % value)13559alt_m = value * 0.01 # cm -> m13560gpi = self.mav.recv_match(13561type='GLOBAL_POSITION_INT',13562blocking=True,13563timeout=113564)13565if gpi is None:13566raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")13567gpi_alt_m = round(gpi.relative_alt * 0.001) # mm -> m13568self.progress("GLOBAL_POSITION_INT relative_alt==%f frsky==%f" % (gpi_alt_m, alt_m))13569if abs(gpi_alt_m - alt_m) < 1:13570return True13571return False1357213573def tfs_validate_gps_speed(self, value):13574self.progress("validating gps speed (0x%02x)" % value)13575speed_ms = value * 0.001 # mm/s -> m/s13576vfr_hud = self.mav.recv_match(13577type='VFR_HUD',13578blocking=True,13579timeout=113580)13581if vfr_hud is None:13582raise NotAchievedException("Did not get VFR_HUD message")13583vfr_hud_speed_ms = round(vfr_hud.groundspeed)13584self.progress("VFR_HUD groundspeed==%f frsky==%f" % (vfr_hud_speed_ms, speed_ms))13585if self.compare_number_percent(vfr_hud_speed_ms, speed_ms, 10):13586return True13587return False1358813589def tfs_validate_yaw(self, value):13590self.progress("validating yaw (0x%02x)" % value)13591yaw_deg = value * 0.01 # cd -> deg13592vfr_hud = self.mav.recv_match(13593type='VFR_HUD',13594blocking=True,13595timeout=113596)13597if vfr_hud is None:13598raise NotAchievedException("Did not get VFR_HUD message")13599vfr_hud_yaw_deg = round(vfr_hud.heading)13600self.progress("VFR_HUD heading==%f frsky==%f" % (vfr_hud_yaw_deg, yaw_deg))13601if self.compare_number_percent(vfr_hud_yaw_deg, yaw_deg, 10):13602return True13603return False1360413605def tfs_validate_vspeed(self, value):13606self.progress("validating vspeed (0x%02x)" % value)13607vspeed_ms = value * 0.01 # cm/s -> m/s13608vfr_hud = self.mav.recv_match(13609type='VFR_HUD',13610blocking=True,13611timeout=113612)13613if vfr_hud is None:13614raise NotAchievedException("Did not get VFR_HUD message")13615vfr_hud_vspeed_ms = round(vfr_hud.climb)13616self.progress("VFR_HUD climb==%f frsky==%f" % (vfr_hud_vspeed_ms, vspeed_ms))13617if self.compare_number_percent(vfr_hud_vspeed_ms, vspeed_ms, 10):13618return True13619return False1362013621def tfs_validate_battery1(self, value):13622self.progress("validating battery1 (0x%02x)" % value)13623voltage_v = value * 0.01 # cV -> V13624batt = self.mav.recv_match(13625type='BATTERY_STATUS',13626blocking=True,13627timeout=5,13628condition="BATTERY_STATUS.id==0"13629)13630if batt is None:13631raise NotAchievedException("Did not get BATTERY_STATUS message")13632battery_status_voltage_v = batt.voltages[0] * 0.001 # mV -> V13633self.progress("BATTERY_STATUS volatge==%f frsky==%f" % (battery_status_voltage_v, voltage_v))13634if self.compare_number_percent(battery_status_voltage_v, voltage_v, 10):13635return True13636return False1363713638def tfs_validate_current1(self, value):13639# test frsky current vs BATTERY_STATUS13640self.progress("validating battery1 (0x%02x)" % value)13641current_a = value * 0.1 # dA -> A13642batt = self.mav.recv_match(13643type='BATTERY_STATUS',13644blocking=True,13645timeout=5,13646condition="BATTERY_STATUS.id==0"13647)13648if batt is None:13649raise NotAchievedException("Did not get BATTERY_STATUS message")13650battery_status_current_a = batt.current_battery * 0.01 # cA -> A13651self.progress("BATTERY_STATUS current==%f frsky==%f" % (battery_status_current_a, current_a))13652if self.compare_number_percent(round(battery_status_current_a * 10), round(current_a * 10), 10):13653return True13654return False1365513656def tfs_validate_fuel(self, value):13657self.progress("validating fuel (0x%02x)" % value)13658fuel = value13659batt = self.mav.recv_match(13660type='BATTERY_STATUS',13661blocking=True,13662timeout=5,13663condition="BATTERY_STATUS.id==0"13664)13665if batt is None:13666raise NotAchievedException("Did not get BATTERY_STATUS message")13667battery_status_fuel = batt.battery_remaining13668self.progress("BATTERY_STATUS fuel==%f frsky==%f" % (battery_status_fuel, fuel))13669if self.compare_number_percent(battery_status_fuel, fuel, 10):13670return True13671return False1367213673def tfs_validate_tmp1(self, value):13674self.progress("validating tmp1 (0x%02x)" % value)13675tmp1 = value13676heartbeat = self.wait_heartbeat()13677heartbeat_tmp1 = heartbeat.custom_mode13678self.progress("GLOBAL_POSITION_INT custom_mode==%f frsky==%f" % (heartbeat_tmp1, tmp1))13679if heartbeat_tmp1 == tmp1:13680return True13681return False1368213683def tfs_validate_tmp2(self, value):13684self.progress("validating tmp2 (0x%02x)" % value)13685tmp2 = value13686gps_raw = self.mav.recv_match(13687type='GPS_RAW_INT',13688blocking=True,13689timeout=113690)13691if gps_raw is None:13692raise NotAchievedException("Did not get GPS_RAW_INT message")13693gps_raw_tmp2 = gps_raw.satellites_visible*10 + gps_raw.fix_type13694self.progress("GPS_RAW_INT tmp2==%f frsky==%f" % (gps_raw_tmp2, tmp2))13695if gps_raw_tmp2 == tmp2:13696return True13697return False1369813699def tfs_validate_rpm(self, value):13700self.progress("validating rpm (0x%02x)" % value)13701tfs_rpm = value13702rpm = self.mav.recv_match(13703type='RPM',13704blocking=True,13705timeout=513706)13707if rpm is None:13708raise NotAchievedException("Did not get RPM message")13709rpm_value = round(rpm.rpm1)13710self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tfs_rpm))13711if rpm_value == tfs_rpm:13712return True13713return False1371413715def wait_rpm1(self, min_rpm=None, timeout=10):13716'''wait for mavlink RPM message to indicate valid RPM'''13717tstart = self.get_sim_time()13718while True:13719t = self.get_sim_time_cached()13720if t - tstart > timeout:13721raise AutoTestTimeoutException("Failed to do get valid RPM")13722rpm = self.mav.recv_match(13723type='RPM',13724blocking=True,13725timeout=113726)13727self.progress("rpm: (%s)" % str(rpm))13728if rpm is None:13729continue13730if min_rpm is None:13731return13732if rpm.rpm1 >= min_rpm:13733return1373413735def FRSkySPort(self):13736'''Test FrSky SPort mode'''13737self.set_parameters({13738"SERIAL5_PROTOCOL": 4, # serial5 is FRSky sport13739"RPM1_TYPE": 10, # enable SITL RPM sensor13740"GPS1_TYPE": 100, # use simulated backend for consistent position13741})13742port = self.spare_network_port()13743self.customise_SITL_commandline([13744"--serial5=tcp:%u" % port # serial5 spews to localhost port13745])13746frsky = FRSkySPort(("127.0.0.1", port), verbose=True)13747self.wait_ready_to_arm()1374813749# we need to start the engine to get some RPM readings, we do it for plane only13750if self.is_plane():13751self.set_autodisarm_delay(0)13752if not self.arm_vehicle():13753raise NotAchievedException("Failed to ARM")13754self.set_rc(3, 1050)13755self.wait_rpm1(timeout=10, min_rpm=200)1375613757self.assert_current_onboard_log_contains_message("RPM")1375813759self.drain_mav()13760# anything with a lambda in here needs a proper test written.13761# This, at least makes sure we're getting some of each13762# message.13763wants = {137640x082F: self.tfs_validate_gps_alt, # gps altitude integer cm137650x040F: self.tfs_validate_tmp1, # Tmp1137660x060F: self.tfs_validate_fuel, # fuel % 0-100137670x041F: self.tfs_validate_tmp2, # Tmp2137680x010F: self.tfs_validate_baro_alt, # baro alt cm137690x083F: self.tfs_validate_gps_speed, # gps speed integer mm/s137700x084F: self.tfs_validate_yaw, # yaw in cd137710x020F: self.tfs_validate_current1, # current dA137720x011F: self.tfs_validate_vspeed, # vertical speed cm/s137730x021F: self.tfs_validate_battery1, # battery 1 voltage cV137740x0800: self.tf_validate_gps, # gps lat/lon137750x050E: self.tfs_validate_rpm, # rpm 113776}13777tstart = self.get_sim_time_cached()13778last_wanting_print = 01377913780last_data_time = None13781while len(wants):13782now = self.get_sim_time()13783if now - last_wanting_print > 1:13784self.progress("Still wanting (%s)" %13785",".join([("0x%02x" % x) for x in wants.keys()]))13786last_wanting_print = now13787wants_copy = copy.copy(wants)13788if now - tstart > 300:13789self.progress("Failed to get frsky passthrough data")13790self.progress("Counts of sensor_id polls sent:")13791frsky.dump_sensor_id_poll_counts_as_progress_messages()13792self.progress("Counts of dataids received:")13793frsky.dump_dataid_counts_as_progress_messages()13794raise AutoTestTimeoutException("Failed to get frsky sport data")13795frsky.update()13796if frsky.last_data_time == last_data_time:13797continue13798last_data_time = frsky.last_data_time13799for want in wants_copy:13800data = frsky.get_data(want)13801if data is None:13802continue13803self.progress("Checking 0x%x" % (want,))13804if wants[want](data):13805self.progress(" Fulfilled")13806del wants[want]13807# ok done, stop the engine13808if self.is_plane():13809self.zero_throttle()13810self.disarm_vehicle(force=True)1381113812def FRSkyD(self):13813'''Test FrSkyD serial output'''13814self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output13815port = self.spare_network_port()13816self.customise_SITL_commandline([13817"--serial5=tcp:%u" % port # serial5 spews to localhost port13818])13819frsky = FRSkyD(("127.0.0.1", port))13820self.wait_ready_to_arm()13821m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)13822gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m1382313824# grab a battery-remaining percentage13825self.run_cmd(13826mavutil.mavlink.MAV_CMD_BATTERY_RESET,13827p1=65535, # battery mask13828p2=96, # percentage13829)13830m = self.assert_receive_message('BATTERY_STATUS', timeout=1)13831want_battery_remaining_pct = m.battery_remaining1383213833tstart = self.get_sim_time_cached()13834have_alt = False13835have_battery = False13836while True:13837t2 = self.get_sim_time_cached()13838if t2 - tstart > 10:13839raise AutoTestTimeoutException("Failed to get frsky D data")13840frsky.update()1384113842alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)13843self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))13844if alt is None:13845continue13846if alt == gpi_abs_alt:13847have_alt = True1384813849batt = frsky.get_data(frsky.dataid_FUEL)13850self.progress("Got batt (%s) mav=%s" % (str(batt), str(want_battery_remaining_pct)))13851if batt is None:13852continue13853if batt == want_battery_remaining_pct:13854have_battery = True1385513856if have_alt and have_battery:13857break13858self.drain_mav()1385913860def test_ltm_g(self, ltm):13861g = ltm.g()13862if g is None:13863return13864m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)13865print("m: %s" % str(m))1386613867print("g.lat=%s m.lat=%s" % (str(g.lat()), str(m.lat)))13868if abs(m.lat - g.lat()) > 10:13869return False1387013871print("g.lon:%s m.lon:%s" % (str(g.lon()), str(m.lon)))13872if abs(m.lon - g.lon()) > 10:13873return False1387413875print("gndspeed: %s" % str(g.gndspeed()))13876if g.gndspeed() != 0:13877# FIXME if we start the vehicle moving.... check against VFR_HUD?13878return False1387913880print("g.alt=%s m.alt=%s" % (str(g.alt()/100.0), str(m.relative_alt/1000.0)))13881if abs(m.relative_alt/1000.0 - g.alt()/100.0) > 1:13882return False1388313884print("sats: %s" % str(g.sats()))13885m = self.mav.recv_match(type='GPS_RAW_INT', blocking=True)13886if m.satellites_visible != g.sats():13887return False1388813889constrained_fix_type = m.fix_type13890if constrained_fix_type > 3:13891constrained_fix_type = 313892print("fix_type: %s" % g.fix_type())13893if constrained_fix_type != g.fix_type():13894return False1389513896return True1389713898def test_ltm_a(self, ltm):13899a = ltm.a()13900if a is None:13901return13902m = self.assert_receive_message('ATTITUDE')1390313904pitch = a.pitch()13905print("pitch: %s" % str(pitch))13906if abs(math.degrees(m.pitch) - pitch) > 1:13907return False1390813909roll = a.roll()13910print("roll: %s" % str(roll))13911if abs(math.degrees(m.roll) - roll) > 1:13912return False1391313914hdg = a.hdg()13915myaw = math.degrees(m.yaw)13916myaw += 36013917myaw %= 36013918print("a.hdg=%s m.hdg=%s" % (str(hdg), str(myaw)))13919if abs(myaw - hdg) > 1:13920return False1392113922return True1392313924def test_ltm_s(self, ltm):13925s = ltm.s()13926if s is None:13927return13928# FIXME. Actually check the field values are correct :-)13929return True1393013931def LTM(self):13932'''Test LTM serial output'''13933self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output13934port = self.spare_network_port()13935self.customise_SITL_commandline([13936"--serial5=tcp:%u" % port # serial5 spews to localhost port13937])13938ltm = LTM(("127.0.0.1", port))13939self.wait_ready_to_arm()1394013941wants = {13942"g": self.test_ltm_g,13943"a": self.test_ltm_a,13944"s": self.test_ltm_s,13945}1394613947tstart = self.get_sim_time()13948while True:13949self.progress("Still wanting (%s)" %13950",".join([("%s" % x) for x in wants.keys()]))13951if len(wants) == 0:13952break13953now = self.get_sim_time_cached()13954if now - tstart > 10:13955raise AutoTestTimeoutException("Failed to get ltm data")1395613957ltm.update()1395813959wants_copy = copy.copy(wants)13960for want in wants_copy:13961self.progress("Checking %s" % (want,))13962if wants[want](ltm):13963self.progress(" Fulfilled")13964del wants[want]1396513966def convertDmsToDdFormat(self, dms):13967deg = math.trunc(dms * 1e-7)13968dd = deg + (((dms * 1.0e-7) - deg) * 100.0 / 60.0)13969if dd < -180.0 or dd > 180.0:13970dd = 0.013971return math.trunc(dd * 1.0e7)1397213973def DEVO(self):13974'''Test DEVO serial output'''13975self.context_push()13976self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output13977port = self.spare_network_port()13978self.customise_SITL_commandline([13979"--serial5=tcp:%u" % port # serial5 spews to localhost port13980])13981devo = DEVO(("127.0.0.1", port))13982self.wait_ready_to_arm()13983m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)1398413985tstart = self.get_sim_time_cached()13986while True:13987self.drain_mav()13988now = self.get_sim_time_cached()13989if now - tstart > 10:13990if devo.frame is not None:13991# we received some frames but could not find correct values13992raise AutoTestTimeoutException("Failed to get correct data")13993else:13994# No frames received. Devo telemetry is compiled out?13995break1399613997devo.update()13998frame = devo.frame13999if frame is None:14000continue1400114002m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)1400314004loc = LocationInt(self.convertDmsToDdFormat(frame.lat()), self.convertDmsToDdFormat(frame.lon()), 0, 0)1400514006print("received lat:%s expected lat:%s" % (str(loc.lat), str(m.lat)))14007print("received lon:%s expected lon:%s" % (str(loc.lon), str(m.lon)))14008dist_diff = self.get_distance_int(loc, m)14009print("Distance:%s" % str(dist_diff))14010if abs(dist_diff) > 2:14011continue1401214013gpi_rel_alt = int(m.relative_alt / 10) # mm -> cm, since driver send alt in cm14014print("received alt:%s expected alt:%s" % (str(frame.alt()), str(gpi_rel_alt)))14015if abs(gpi_rel_alt - frame.alt()) > 10:14016continue1401714018print("received gndspeed: %s" % str(frame.speed()))14019if frame.speed() != 0:14020# FIXME if we start the vehicle moving.... check against VFR_HUD?14021continue1402214023print("received temp:%s expected temp:%s" % (str(frame.temp()), str(self.mav.messages['HEARTBEAT'].custom_mode)))14024if frame.temp() != self.mav.messages['HEARTBEAT'].custom_mode:14025# currently we receive mode as temp. This should be fixed when driver is updated14026continue1402714028# we match the received voltage with the voltage of primary instance14029batt = self.mav.recv_match(14030type='BATTERY_STATUS',14031blocking=True,14032timeout=5,14033condition="BATTERY_STATUS.id==0"14034)14035if batt is None:14036raise NotAchievedException("Did not get BATTERY_STATUS message")14037volt = batt.voltages[0]*0.00114038print("received voltage:%s expected voltage:%s" % (str(frame.volt()*0.1), str(volt)))14039if abs(frame.volt()*0.1 - volt) > 0.1:14040continue14041# if we reach here, exit14042break14043self.context_pop()14044self.reboot_sitl()1404514046def MSP_DJI(self):14047'''Test MSP DJI serial output'''14048self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output14049self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode14050port = self.spare_network_port()14051self.customise_SITL_commandline([14052"--serial5=tcp:%u" % port # serial5 spews to localhost port14053])14054msp = MSP_DJI(("127.0.0.1", port))14055self.wait_ready_to_arm()1405614057tstart = self.get_sim_time()14058while True:14059self.drain_mav()14060if self.get_sim_time_cached() - tstart > 10:14061raise NotAchievedException("Did not get location")14062msp.update()14063try:14064f = msp.get_frame(msp.FRAME_GPS_RAW)14065except KeyError:14066continue14067dist = self.get_distance_int(f.LocationInt(), self.sim_location_int())14068print("lat=%f lon=%f dist=%f" % (f.lat(), f.lon(), dist))14069if dist < 1:14070break1407114072def CRSF(self):14073'''Test RC CRSF'''14074self.context_push()14075ex = None14076try:14077self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input14078port = self.spare_network_port()14079self.customise_SITL_commandline([14080"--serial5=tcp:%u" % port # serial5 reads from to localhost port14081])14082crsf = CRSF(("127.0.0.1", port))14083crsf.connect()1408414085self.progress("Writing vtx_frame")14086crsf.write_data_id(crsf.dataid_vtx_frame)14087self.delay_sim_time(5)14088self.progress("Writing vtx_telem")14089crsf.write_data_id(crsf.dataid_vtx_telem)14090self.delay_sim_time(5)14091self.progress("Writing vtx_unknown")14092crsf.write_data_id(crsf.dataid_vtx_unknown)14093self.delay_sim_time(5)14094except Exception as e:14095self.print_exception_caught(e)14096ex = e14097self.context_pop()14098self.disarm_vehicle(force=True)14099self.reboot_sitl()14100if ex is not None:14101raise ex1410214103def CompassPrearms(self):14104'''test compass prearm checks'''14105self.wait_ready_to_arm()14106# XY are checked specially:14107for axis in 'X', 'Y': # ArduPilot only checks these two axes14108self.context_push()14109self.set_parameter(f"COMPASS_OFS2_{axis}", 1000)14110self.assert_prearm_failure("Compasses inconsistent")14111self.context_pop()14112self.wait_ready_to_arm()1411314114# now test the total anglular difference:14115self.context_push()14116self.set_parameters({14117"COMPASS_OFS2_X": 1000,14118"COMPASS_OFS2_Y": -1000,14119"COMPASS_OFS2_Z": -10000,14120})14121self.assert_prearm_failure("Compasses inconsistent")14122self.context_pop()14123self.wait_ready_to_arm()14124# the following line papers over a probably problem with the14125# EKF recovering from bad compass offsets. Without it, the14126# EKF will maintain a 10-degree offset from the true compass14127# heading seemingly indefinitely.14128self.reboot_sitl()1412914130def run_replay(self, filepath):14131'''runs replay in filepath, returns filepath to Replay logfile'''14132util.run_cmd(14133['build/sitl/tool/Replay', filepath],14134directory=util.topdir(),14135checkfail=True,14136show=True,14137output=True,14138)14139return self.current_onboard_log_filepath()1414014141def AHRS_ORIENTATION(self):14142'''test AHRS_ORIENTATION parameter works'''14143self.context_push()14144self.wait_ready_to_arm()14145original_imu = self.assert_receive_message("RAW_IMU", verbose=True)14146self.set_parameter("AHRS_ORIENTATION", 16) # roll-9014147self.delay_sim_time(2) # we update this on a timer14148new_imu = self.assert_receive_message("RAW_IMU", verbose=True)14149delta_zacc = original_imu.zacc - new_imu.zacc14150delta_z_g = delta_zacc/1000.0 # milligravities -> gravities14151if delta_z_g - 1 > 0.1: # milligravities....14152raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_z_g=%f)" % (delta_z_g,))14153delta_yacc = original_imu.yacc - new_imu.yacc14154delta_y_g = delta_yacc/1000.0 # milligravities -> gravities14155if delta_y_g + 1 > 0.1:14156raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_y_g=%f)" % (delta_y_g,))14157self.context_pop()14158self.reboot_sitl()14159self.delay_sim_time(2) # we update orientation on a timer1416014161def GPSTypes(self):14162'''check each simulated GPS works'''14163self.reboot_sitl()14164orig = self.poll_home_position(timeout=60)14165sim_gps = [14166# (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix)14167# if gps_type is None we auto-detect14168# (0, "NONE"),14169(1, "UBLOX", None, "u-blox", 5, 'probing'),14170(5, "NMEA", 5, "NMEA", 5, 'probing'),14171(6, "SBP", None, "SBP", 5, 'probing'),14172(8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS14173(9, "SBP2", None, "SBP2", 5, 'probing'),14174(10, "SBF", 10, 'SBF', 5, 'probing'),14175(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS14176(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS14177# (9, "FILE"),14178]14179self.context_collect("STATUSTEXT")14180for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:14181self.start_subtest("Checking GPS type %s" % name)14182self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)14183self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)14184if gps_type is None:14185gps_type = 1 # auto-detect14186self.set_parameter("GPS1_TYPE", gps_type)14187self.context_clear_collection('STATUSTEXT')14188self.reboot_sitl()14189if detect_prefix == "probing":14190self.wait_statustext(f"probing for {detect_name}", check_context=True)14191else:14192self.wait_statustext(f"specified as {detect_name}", check_context=True)14193self.wait_statustext(f"detected {detect_name}", check_context=True)14194n = self.poll_home_position(timeout=120)14195distance = self.get_distance_int(orig, n)14196if distance > 1:14197raise NotAchievedException(f"gps type {name} misbehaving")1419814199def assert_gps_satellite_count(self, messagename, count):14200m = self.assert_receive_message(messagename)14201if m.satellites_visible != count:14202raise NotAchievedException("Expected %u sats, got %u" %14203(count, m.satellites_visible))1420414205def check_attitudes_match(self):14206'''make sure ahrs2 and simstate and ATTTIUDE_QUATERNION all match'''1420714208# these are ordered to bookend the list with timestamps (which14209# both attitude messages have):14210get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']14211msgs = self.get_messages_frame(get_names)1421214213for get_name in get_names:14214self.progress("%s: %s" % (get_name, msgs[get_name]))1421514216simstate = msgs['SIMSTATE']14217attitude = msgs['ATTITUDE']14218ahrs2 = msgs['AHRS2']14219attitude_quaternion = msgs['ATTITUDE_QUATERNION']1422014221# check ATTITUDE14222want = math.degrees(simstate.roll)14223got = math.degrees(attitude.roll)14224if abs(mavextra.angle_diff(want, got)) > 20:14225raise NotAchievedException("ATTITUDE.Roll looks bad (want=%f got=%f)" %14226(want, got))14227want = math.degrees(simstate.pitch)14228got = math.degrees(attitude.pitch)14229if abs(mavextra.angle_diff(want, got)) > 20:14230raise NotAchievedException("ATTITUDE.Pitch looks bad (want=%f got=%f)" %14231(want, got))1423214233# check AHRS214234want = math.degrees(simstate.roll)14235got = math.degrees(ahrs2.roll)14236if abs(mavextra.angle_diff(want, got)) > 20:14237raise NotAchievedException("AHRS2.Roll looks bad (want=%f got=%f)" %14238(want, got))1423914240want = math.degrees(simstate.pitch)14241got = math.degrees(ahrs2.pitch)14242if abs(mavextra.angle_diff(want, got)) > 20:14243raise NotAchievedException("AHRS2.Pitch looks bad (want=%f got=%f)" %14244(want, got))1424514246# check ATTITUDE_QUATERNION14247q = quaternion.Quaternion([14248attitude_quaternion.q1,14249attitude_quaternion.q2,14250attitude_quaternion.q3,14251attitude_quaternion.q414252])14253euler = q.euler14254self.progress("attquat:%s q:%s euler:%s" % (14255str(attitude_quaternion), q, euler))1425614257want = math.degrees(simstate.roll)14258got = math.degrees(euler[0])14259if mavextra.angle_diff(want, got) > 20:14260raise NotAchievedException("quat roll differs from attitude roll; want=%f got=%f" %14261(want, got))1426214263want = math.degrees(simstate.pitch)14264got = math.degrees(euler[1])14265if mavextra.angle_diff(want, got) > 20:14266raise NotAchievedException("quat pitch differs from attitude pitch; want=%f got=%f" %14267(want, got))1426814269def MultipleGPS(self):14270'''check ArduPilot behaviour across multiple GPS units'''14271self.assert_message_rate_hz('GPS2_RAW', 0)1427214273# we start sending GPS2_TYPE - but it will never actually be14274# filled in as _port[1] is only filled in in AP_GPS::init()14275self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")14276self.set_parameter("GPS2_TYPE", 1)14277self.assert_message_rate_hz('GPS2_RAW', 5)1427814279self.start_subtest("Ensure correct fix type when no connected GPS")14280m = self.assert_receive_message("GPS2_RAW")14281self.progress(self.dump_message_verbose(m))14282if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_NO_GPS:14283raise NotAchievedException("Incorrect fix type")1428414285self.start_subtest("Ensure detection when sim gps connected")14286self.set_parameter("SIM_GPS2_TYPE", 1)14287self.set_parameter("SIM_GPS2_ENABLE", 1)14288# a reboot is required after setting GPS2_TYPE. We start14289# sending GPS2_RAW out, once the parameter is set, but a14290# reboot is required because _port[1] is only set in14291# AP_GPS::init() at boot time, so it will never be detected.14292self.context_collect("STATUSTEXT")14293self.reboot_sitl()14294self.wait_statustext("GPS 1: detected u-blox", check_context=True)14295self.wait_statustext("GPS 2: detected u-blox", check_context=True)14296m = self.assert_receive_message("GPS2_RAW")14297self.progress(self.dump_message_verbose(m))14298# would be nice for it to take some time to get a fix....14299if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_RTK_FIXED:14300raise NotAchievedException("Incorrect fix type")1430114302self.start_subtest("Check parameters are per-GPS")14303self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)14304self.assert_gps_satellite_count("GPS_RAW_INT", 10)14305self.set_parameter("SIM_GPS1_NUMSATS", 13)14306self.assert_gps_satellite_count("GPS_RAW_INT", 13)1430714308self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)14309self.assert_gps_satellite_count("GPS2_RAW", 10)14310self.set_parameter("SIM_GPS2_NUMSATS", 12)14311self.assert_gps_satellite_count("GPS2_RAW", 12)1431214313self.start_subtest("check that GLOBAL_POSITION_INT fails over")14314m = self.assert_receive_message("GLOBAL_POSITION_INT")14315gpi_alt = m.alt14316for msg in ["GPS_RAW_INT", "GPS2_RAW"]:14317m = self.assert_receive_message(msg)14318if abs(m.alt - gpi_alt) > 100: # these are in mm14319raise NotAchievedException("Alt (%s) discrepancy; %d vs %d" %14320(msg, m.alt, gpi_alt))14321introduced_error = 10 # in metres14322self.set_parameter("SIM_GPS2_ALT_OFS", introduced_error)14323self.do_timesync_roundtrip()14324m = self.assert_receive_message("GPS2_RAW")14325if abs((m.alt-introduced_error*1000) - gpi_alt) > 100:14326raise NotAchievedException("skewed Alt (%s) discrepancy; %d+%d vs %d" %14327(msg, introduced_error*1000, m.alt, gpi_alt))14328m = self.assert_receive_message("GLOBAL_POSITION_INT")14329new_gpi_alt = m.alt14330if abs(gpi_alt - new_gpi_alt) > 100:14331raise NotAchievedException("alt moved unexpectedly")14332self.progress("Killing first GPS")14333self.set_parameter("SIM_GPS1_ENABLE", 0)14334self.delay_sim_time(1)14335self.progress("Checking altitude now matches second GPS")14336m = self.assert_receive_message("GLOBAL_POSITION_INT")14337new_gpi_alt2 = m.alt14338m = self.assert_receive_message("GPS2_RAW")14339if abs(new_gpi_alt2 - m.alt) > 100:14340raise NotAchievedException("Failover not detected")1434114342def fetch_file_via_ftp(self, path, timeout=20):14343'''returns the content of the FTP'able file at path'''14344self.progress("Retrieving (%s) using MAVProxy" % path)14345mavproxy = self.start_mavproxy()14346mavproxy.expect("Saved .* parameters to")14347ex = None14348tmpfile = tempfile.NamedTemporaryFile(mode='r', delete=False)14349try:14350mavproxy.send("module load ftp\n")14351mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])14352mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message14353mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))14354mavproxy.expect("Getting")14355tstart = self.get_sim_time()14356while True:14357now = self.get_sim_time()14358if now - tstart > timeout:14359raise NotAchievedException("expected complete transfer")14360self.progress("Polling status")14361mavproxy.send("ftp status\n")14362try:14363mavproxy.expect("No transfer in progress", timeout=1)14364break14365except Exception:14366continue14367# terminate the connection, or it may still be in progress the next time an FTP is attempted:14368mavproxy.send("ftp cancel\n")14369mavproxy.expect("Terminated session")14370except Exception as e:14371self.print_exception_caught(e)14372ex = e1437314374self.stop_mavproxy(mavproxy)1437514376if ex is not None:14377raise ex1437814379return tmpfile.read()1438014381def MAVFTP(self):14382'''ensure MAVProxy can do MAVFTP to ardupilot'''14383mavproxy = self.start_mavproxy()14384ex = None14385try:14386mavproxy.send("module load ftp\n")14387mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])14388mavproxy.send("ftp list\n")14389some_directory = None14390for entry in sorted(os.listdir(".")):14391if os.path.isdir(entry):14392some_directory = entry14393break14394if some_directory is None:14395raise NotAchievedException("No directories?!")14396expected_line = " D %s" % some_directory14397mavproxy.expect(expected_line) # one line from the ftp list output14398except Exception as e:14399self.print_exception_caught(e)14400ex = e1440114402self.stop_mavproxy(mavproxy)1440314404if ex is not None:14405raise ex1440614407def write_content_to_filepath(self, content, filepath):14408'''write biunary content to filepath'''14409with open(filepath, "wb") as f:14410if sys.version_info.major >= 3:14411if not isinstance(content, bytes):14412raise NotAchievedException("Want bytes to write_content_to_filepath")14413f.write(content)14414f.close()1441514416def add_embedded_params_to_binary(self, binary, defaults):14417sys.path.insert(1, os.path.join(self.rootdir(), 'Tools', 'scripts'))14418import apj_tool1441914420# copy binary14421if getattr(self, "embedded_default_counter", None) is None:14422self.embedded_default_counter = 014423self.embedded_default_counter += 11442414425new_filepath = binary + "-newdefaults-%u" % self.embedded_default_counter14426shutil.copy(binary, new_filepath)1442714428# create file for defaults14429defaults_filepath = "embed-these-defaults.txt"14430self.write_content_to_filepath(defaults.encode('utf-8'), defaults_filepath)1443114432# do the needful14433a = apj_tool.embedded_defaults(new_filepath)14434if not a.find():14435raise NotAchievedException("Did not find defaults")14436a.set_file(defaults_filepath)14437a.save()1443814439return new_filepath1444014441def sample_param_file_content(self):14442'''returns an array of tuples, (param file content, dictionary of what14443parameter values should be tested afterwards)'''14444dashes = "-" * 15014445return [14446# multiple lines:14447("""SERIAL5_BAUD 123414448SERIAL4_BAUD=456714449""", {"SERIAL5_BAUD": 1234, "SERIAL4_BAUD": 4567}),1445014451# line missing CR:14452("""SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 6789}),1445314454# commented-out line:14455("""# SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 57}),1445614457# very long comment line followed by more text:14458("""SERIAL4_BAUD 678914459# awesome dashes: %s14460SERIAL5_BAUD 12814461""" % dashes, {"SERIAL4_BAUD": 6789, "SERIAL5_BAUD": 128}),1446214463]1446414465def EmbeddedParamParser(self):14466'''check parsing of embedded defaults file'''14467# warning: don't try this test on Copter as it won't boot14468# without the passed-in file (which we don't parse if there14469# are embedded defaults)14470for (content, param_values) in self.sample_param_file_content():14471binary_with_defaults = self.add_embedded_params_to_binary(self.binary, content)14472self.customise_SITL_commandline([], binary=binary_with_defaults)14473self.assert_parameter_values(param_values)1447414475def _MotorTest(self,14476command,14477timeout=60,14478mot1_servo_chan=1,14479mot4_servo_chan=4,14480wait_finish_text=True,14481quadplane=False):14482'''Run Motor Tests (with specific mavlink message)'''14483self.start_subtest("Testing PWM output")14484pwm_in = 130014485# default frame is "+" - start motor of 2 is "B", which is14486# motor 1... see14487# https://ardupilot.org/copter/docs/connect-escs-and-motors.html14488command(14489mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,14490p1=2, # start motor14491p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,14492p3=pwm_in, # pwm-to-output14493p4=2, # timeout in seconds14494p5=2, # number of motors to output14495p6=0, # compass learning14496timeout=timeout,14497)14498# long timeouts here because there's a pause before we start motors14499self.wait_servo_channel_value(mot1_servo_chan, pwm_in, timeout=10)14500self.wait_servo_channel_value(mot4_servo_chan, pwm_in, timeout=10)14501if wait_finish_text:14502self.wait_statustext("finished motor test")14503self.wait_disarmed()14504# wait_disarmed is not sufficient here; it's actually the14505# *motors* being armed which causes the problem, not the14506# vehicle's arm state! Could we use SYS_STATUS here instead?14507self.delay_sim_time(10)14508self.end_subtest("Testing PWM output")1450914510self.start_subtest("Testing percentage output")14511percentage = 90.114512# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC314513# min/max are used.14514expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.014515# quadplane doesn't use the expect value - it wants 190014516# rather than the calculated 1901...14517if quadplane:14518expected_pwm = 190014519self.progress("expected pwm=%f" % expected_pwm)14520command(14521mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,14522p1=2, # start motor14523p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,14524p3=percentage, # pwm-to-output14525p4=2, # timeout in seconds14526p5=2, # number of motors to output14527p6=0, # compass learning14528timeout=timeout,14529)14530self.wait_servo_channel_value(mot1_servo_chan, expected_pwm, timeout=10)14531self.wait_servo_channel_value(mot4_servo_chan, expected_pwm, timeout=10)14532if wait_finish_text:14533self.wait_statustext("finished motor test")14534self.wait_disarmed()14535# wait_disarmed is not sufficient here; it's actually the14536# *motors* being armed which causes the problem, not the14537# vehicle's arm state! Could we use SYS_STATUS here instead?14538self.delay_sim_time(10)14539self.end_subtest("Testing percentage output")1454014541def MotorTest(self, timeout=60, **kwargs):14542'''Run Motor Tests''' # common to Copter and QuadPlane14543self._MotorTest(self.run_cmd, **kwargs)14544self._MotorTest(self.run_cmd_int, **kwargs)1454514546def test_ibus_voltage(self, message):14547batt = self.mav.recv_match(14548type='BATTERY_STATUS',14549blocking=True,14550timeout=5,14551condition="BATTERY_STATUS.id==0"14552)14553if batt is None:14554raise NotAchievedException("Did not get BATTERY_STATUS message")14555want = int(batt.voltages[0] * 0.1)1455614557if want != message.get_sensor_value():14558raise NotAchievedException("Bad voltage (want=%u got=%u)" %14559(want, message.get_sensor_value()))14560self.progress("iBus voltage OK")1456114562def test_ibus_armed(self, message):14563got = message.get_sensor_value()14564want = 1 if self.armed() else 014565if got != want:14566raise NotAchievedException("Expected armed %u got %u" %14567(want, got))14568self.progress("iBus armed OK")1456914570def test_ibus_mode(self, message):14571got = message.get_sensor_value()14572want = self.mav.messages['HEARTBEAT'].custom_mode14573if got != want:14574raise NotAchievedException("Expected mode %u got %u" %14575(want, got))14576self.progress("iBus mode OK")1457714578def test_ibus_get_response(self, ibus, timeout=5):14579tstart = self.get_sim_time()14580while True:14581now = self.get_sim_time()14582if now - tstart > timeout:14583raise AutoTestTimeoutException("Failed to get ibus data")14584packet = ibus.update()14585if packet is not None:14586return packet1458714588def IBus(self):14589'''test the IBus protocol'''14590self.set_parameter("SERIAL5_PROTOCOL", 49)14591self.customise_SITL_commandline([14592"--serial5=tcp:6735" # serial5 spews to localhost:673514593])14594ibus = IBus(("127.0.0.1", 6735))14595ibus.connect()1459614597# expected_sensors should match the list created in AP_IBus_Telem14598expected_sensors = {14599# sensor id : (len, IBUS_MEAS_TYPE_*, test_function)146001: (2, 0x15, self.test_ibus_armed),146012: (2, 0x16, self.test_ibus_mode),146025: (2, 0x03, self.test_ibus_voltage),14603}1460414605for (sensor_addr, results) in expected_sensors.items():14606# first make sure it is present:14607request = IBusRequest_DISCOVER(sensor_addr)14608ibus.port.sendall(request.for_wire())1460914610packet = self.test_ibus_get_response(ibus)14611if packet.address != sensor_addr:14612raise ValueError("Unexpected sensor address %u" %14613(packet.address,))1461414615(expected_length, expected_type, validator) = results1461614617self.progress("Getting sensor (%x) type" % (sensor_addr))14618request = IBusRequest_GET_SENSOR_TYPE(sensor_addr)14619ibus.port.sendall(request.for_wire())1462014621packet = self.test_ibus_get_response(ibus)14622if packet.address != sensor_addr:14623raise ValueError("Unexpected sensor address %u" %14624(packet.address,))1462514626if packet.sensor_type != expected_type:14627raise ValueError("Unexpected sensor type want=%u got=%u" %14628(expected_type, packet.sensor_type))1462914630if packet.sensor_length != expected_length:14631raise ValueError("Unexpected sensor len want=%u got=%u" %14632(expected_length, packet.sensor_length))1463314634self.progress("Getting sensor (%x) value" % (sensor_addr))14635request = IBusRequest_GET_SENSOR_VALUE(sensor_addr)14636ibus.port.sendall(request.for_wire())1463714638packet = self.test_ibus_get_response(ibus)14639validator(packet)1464014641# self.progress("Ensure we cover all sensors")14642# for i in range(1, 17): # zero is special14643# if i in expected_sensors:14644# continue14645# request = IBusRequest_DISCOVER(i)14646# ibus.port.sendall(request.for_wire())1464714648# try:14649# packet = self.test_ibus_get_response(ibus, timeout=1)14650# except AutoTestTimeoutException:14651# continue14652# self.progress("Received packet (%s)" % str(packet))14653# raise NotAchievedException("IBus sensor %u is untested" % i)1465414655def tests(self):14656return [14657self.PIDTuning,14658self.ArmFeatures,14659self.SetHome,14660self.ConfigErrorLoop,14661self.CPUFailsafe,14662self.Parameters,14663self.LoggerDocumentation,14664self.Logging,14665self.GetCapabilities,14666self.InitialMode,14667]1466814669def post_tests_announcements(self):14670if self._show_test_timings:14671if self.waiting_to_arm_count == 0:14672avg = None14673else:14674avg = self.total_waiting_to_arm_time/self.waiting_to_arm_count14675self.progress("Spent %f seconds waiting to arm. count=%u avg=%s" %14676(self.total_waiting_to_arm_time,14677self.waiting_to_arm_count,14678str(avg)))14679self.show_test_timings()14680if self.forced_post_test_sitl_reboots != 0:14681print("Had to force-reset SITL %u times" %14682(self.forced_post_test_sitl_reboots,))1468314684def autotest(self, tests=None, allow_skips=True, step_name=None):14685"""Autotest used by ArduPilot autotest CI."""14686if tests is None:14687tests = self.tests()14688all_tests = []14689for test in tests:14690if not isinstance(test, Test):14691test = Test(test)14692all_tests.append(test)1469314694disabled = self.disabled_tests()14695if not allow_skips:14696disabled = {}14697skip_list = []14698tests = []14699seen_test_name = set()14700for test in all_tests:14701if test.name in seen_test_name:14702raise ValueError("Duplicate test name %s" % test.name)14703seen_test_name.add(test.name)14704if test.name in disabled:14705self.progress("##### %s is skipped: %s" % (test, disabled[test.name]))14706skip_list.append((test, disabled[test.name]))14707continue14708tests.append(test)1470914710results = self.run_tests(tests)1471114712if len(skip_list):14713self.progress("Skipped tests:")14714for skipped in skip_list:14715(test, reason) = skipped14716print(" %s (see %s)" % (test.name, reason))1471714718self.fail_list = list(filter(lambda x : not x.passed, results))14719if len(self.fail_list):14720self.progress("Failing tests:")14721for failure in self.fail_list:14722print(str(failure))1472314724self.post_tests_announcements()14725if self.generate_junit:14726if step_name is None:14727step_name = "Unknown_step_name"14728step_name.replace(".", "_")14729self.create_junit_report(step_name, results, skip_list)1473014731return len(self.fail_list) == 01473214733def create_junit_report(self, test_name: str, results: List[Result], skip_list: List[Tuple[Test, Dict[str, str]]]) -> None:14734"""Generate Junit report from the autotest results"""14735from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure14736frame = self.vehicleinfo_key()14737xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml"14738self.progress(f"Writing test result in jUnit format to {xml_filename}\n")1473914740suite = TestSuite(f"Autotest {frame} {test_name}")14741suite.timestamp = datetime.now().replace(microsecond=0).isoformat()14742for result in results:14743case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed)14744# f"{result.test.description}"14745# case.file ## TODO : add file properties to match test location14746if not result.passed:14747case.result = [Failure(f"see {result.debug_filename}", f"{result.exception}")]14748suite.add_testcase(case)14749for skipped in skip_list:14750(test, reason) = skipped14751case = TestCase(f"{test.name}", f"{test.function}")14752case.result = [Skipped(f"Skipped : {reason}")]1475314754suite.add_property("Firmware Version Major", self.fcu_firmware_version[0])14755suite.add_property("Firmware Version Minor", self.fcu_firmware_version[1])14756suite.add_property("Firmware Version Rev", self.fcu_firmware_version[2])14757suite.add_property("Firmware hash", self.fcu_firmware_hash)14758suite.add_property("Git hash", self.githash)14759mavproxy_version = util.MAVProxy_version()14760suite.add_property("Mavproxy Version Major", mavproxy_version[0])14761suite.add_property("Mavproxy Version Minor", mavproxy_version[1])14762suite.add_property("Mavproxy Version Rev", mavproxy_version[2])1476314764xml = JUnitXml()14765xml.add_testsuite(suite)14766xml.write(xml_filename, pretty=True)1476714768def mavfft_fttd(self, sensor_type, sensor_instance, since, until):14769'''display fft for raw ACC data in current logfile'''1477014771'''object to store data about a single FFT plot'''14772class MessageData(object):14773def __init__(self, ffth):14774self.seqno = -114775self.fftnum = ffth.N14776self.sensor_type = ffth.type14777self.instance = ffth.instance14778self.sample_rate_hz = ffth.smp_rate14779self.multiplier = ffth.mul14780self.sample_us = ffth.SampleUS14781self.data = {}14782self.data["X"] = []14783self.data["Y"] = []14784self.data["Z"] = []14785self.holes = False14786self.freq = None1478714788def add_fftd(self, fftd):14789self.seqno += 114790self.data["X"].extend(fftd.x)14791self.data["Y"].extend(fftd.y)14792self.data["Z"].extend(fftd.z)1479314794mlog = self.dfreader_for_current_onboard_log()1479514796# see https://holometer.fnal.gov/GH_FFT.pdf for a description of the techniques used here14797messages = []14798messagedata = None14799while True:14800m = mlog.recv_match()14801if m is None:14802break14803msg_type = m.get_type()14804if msg_type == "ISBH":14805if messagedata is not None:14806if (messagedata.sensor_type == sensor_type and14807messagedata.instance == sensor_instance and14808messagedata.sample_us > since and14809messagedata.sample_us < until):14810messages.append(messagedata)14811messagedata = MessageData(m)14812continue1481314814if msg_type == "ISBD":14815if (messagedata is not None and14816messagedata.sensor_type == sensor_type and14817messagedata.instance == sensor_instance):14818messagedata.add_fftd(m)1481914820fft_len = len(messages[0].data["X"])14821sum_fft = {14822"X": numpy.zeros(int(fft_len / 2 + 1)),14823"Y": numpy.zeros(int(fft_len / 2 + 1)),14824"Z": numpy.zeros(int(fft_len / 2 + 1)),14825}14826sample_rate = 014827counts = 014828window = numpy.hanning(fft_len)14829# The returned float array f contains the frequency bin centers in cycles per unit of the14830# sample spacing (with zero at the start).14831freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz)1483214833# calculate NEBW constant14834S2 = numpy.inner(window, window)1483514836for message in messages:14837for axis in ["X", "Y", "Z"]:14838# normalize data and convert to dps in order to produce more meaningful magnitudes14839if message.sensor_type == 1:14840d = numpy.array(numpy.degrees(message.data[axis])) / float(message.multiplier)14841else:14842d = numpy.array(message.data[axis]) / float(message.multiplier)1484314844# apply window to the input14845d *= window14846# perform RFFT14847d_fft = numpy.fft.rfft(d)14848# convert to squared complex magnitude14849d_fft = numpy.square(abs(d_fft))14850# remove DC component14851d_fft[0] = 014852d_fft[-1] = 014853# accumulate the sums14854sum_fft[axis] += d_fft1485514856sample_rate = message.sample_rate_hz14857counts += 11485814859numpy.seterr(divide='ignore')14860psd = {}14861for axis in ["X", "Y", "Z"]:14862# normalize output to averaged PSD14863psd[axis] = 2 * (sum_fft[axis] / counts) / (sample_rate * S2)14864psd[axis] = 10 * numpy.log10(psd[axis])1486514866psd["F"] = freqmap1486714868return psd1486914870def model_defaults_filepath(self, model):14871vehicle = self.vehicleinfo_key()14872vinfo = vehicleinfo.VehicleInfo()14873defaults_filepath = vinfo.options[vehicle]["frames"][model]["default_params_filename"]14874if isinstance(defaults_filepath, str):14875defaults_filepath = [defaults_filepath]14876defaults_list = []14877for d in defaults_filepath:14878defaults_list.append(util.reltopdir(os.path.join(testdir, d)))14879return defaults_list1488014881def load_default_params_file(self, filename):14882'''load a file from Tools/autotest/default_params'''14883filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename))14884self.repeatedly_apply_parameter_filepath(filepath)1488514886def load_params_file(self, filename):14887'''load a file from test-specific directory'''14888filepath = os.path.join(testdir, self.current_test_name_directory, filename)14889self.repeatedly_apply_parameter_filepath(filepath)1489014891def send_pause_command(self):14892'''pause AUTO/GUIDED modes'''14893self.run_cmd(14894mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,14895p1=0, # 0: pause, 1: continue14896)1489714898def send_resume_command(self):14899'''resume AUTO/GUIDED modes'''14900self.run_cmd(14901mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,14902p1=1, # 0: pause, 1: continue14903)1490414905def enum_state_name(self, enum_name, state, pretrim=None):14906e = mavutil.mavlink.enums[enum_name]14907e_value = e[state]14908name = e_value.name14909if pretrim is not None:14910if not pretrim.startswith(pretrim):14911raise NotAchievedException("Expected %s to pretrim" % (pretrim))14912name = name.replace(pretrim, "")14913return name1491414915def vtol_state_name(self, state):14916return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_")1491714918def landed_state_name(self, state):14919return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_")1492014921def assert_extended_sys_state(self, vtol_state, landed_state):14922m = self.assert_receive_message('EXTENDED_SYS_STATE', timeout=1)14923if m.vtol_state != vtol_state:14924raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" %14925(self.vtol_state_name(vtol_state),14926self.vtol_state_name(m.vtol_state)))14927if m.landed_state != landed_state:14928raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" %14929(self.landed_state_name(landed_state),14930self.landed_state_name(m.landed_state)))1493114932def wait_extended_sys_state(self, vtol_state, landed_state, timeout=10):14933tstart = self.get_sim_time()14934while True:14935if self.get_sim_time() - tstart > timeout:14936raise NotAchievedException("Did not achieve vol/landed states")14937self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" %14938(self.vtol_state_name(vtol_state),14939self.landed_state_name(landed_state)))14940m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True)14941if m.landed_state != landed_state:14942self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" %14943(self.landed_state_name(landed_state),14944self.landed_state_name(m.landed_state)))14945continue14946if m.vtol_state != vtol_state:14947self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" %14948(self.vtol_state_name(vtol_state),14949self.vtol_state_name(m.vtol_state)))14950continue1495114952self.progress("vtol and landed states match")14953return1495414955def setGCSfailsafe(self, paramValue):14956# Slow down the sim rate if GCS Failsafe is in use14957if paramValue == 0:14958self.set_parameters({14959"FS_GCS_ENABLE": paramValue,14960"SIM_SPEEDUP": 10,14961})14962else:14963self.set_parameters({14964"SIM_SPEEDUP": 4,14965"FS_GCS_ENABLE": paramValue,14966})149671496814969