Path: blob/master/Tools/autotest/vehicle_test_suite.py
9798 views
'''1Common base class for each of the autotest suites23AP_FLAKE8_CLEAN45'''67from __future__ import annotations89import abc10import copy11import errno12import glob13import io14import math15import os16import pathlib17import re18import shutil19import signal20import sys21import time22import traceback23from datetime import datetime24from typing import List25from typing import Tuple26from typing import Dict27import importlib.util2829import pexpect30import fnmatch31import operator32import numpy33import socket34import struct35import random36import tempfile37import threading38import enum39from inspect import currentframe, getframeinfo40from pathlib import Path4142from MAVProxy.modules.lib import mp_util43from MAVProxy.modules.lib import mp_elevation4445from pymavlink import mavparm46from pymavlink import mavwp, mavutil, DFReader47from pymavlink import mavextra48from pymavlink.rotmat import Vector349from pymavlink import quaternion50from pymavlink.generator import mavgen5152from pysim import util, vehicleinfo5354try:55import queue as Queue56except ImportError:57import Queue585960# Enumeration convenience class for mavlink POSITION_TARGET_TYPEMASK61class MAV_POS_TARGET_TYPE_MASK(enum.IntEnum):62POS_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |63mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |64mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE)65VEL_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |66mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |67mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE)68ACC_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |69mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |70mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE)71FORCE_SET = mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET72YAW_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE73YAW_RATE_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE74POS_ONLY = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE75ALT_ONLY = (VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE |76mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |77mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE)78IGNORE_ALL = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE | POS_IGNORE79LAST_BYTE = 0xF000808182MAV_FRAMES_TO_TEST = [83mavutil.mavlink.MAV_FRAME_GLOBAL,84mavutil.mavlink.MAV_FRAME_GLOBAL_INT,85mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,86mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,87mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,88mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT89]9091# get location of scripts92testdir = os.path.dirname(os.path.realpath(__file__))9394try:95from itertools import izip as zip96except ImportError:97# probably python298pass99100101class ErrorException(Exception):102"""Base class for other exceptions"""103pass104105106class AutoTestTimeoutException(ErrorException):107pass108109110class WaitModeTimeout(AutoTestTimeoutException):111"""Thrown when fails to achieve given mode change."""112pass113114115class WaitAltitudeTimout(AutoTestTimeoutException):116"""Thrown when fails to achieve given altitude range."""117pass118119120class WaitGroundSpeedTimeout(AutoTestTimeoutException):121"""Thrown when fails to achieve given ground speed range."""122pass123124125class WaitRollTimeout(AutoTestTimeoutException):126"""Thrown when fails to achieve given roll in degrees."""127pass128129130class WaitPitchTimeout(AutoTestTimeoutException):131"""Thrown when fails to achieve given pitch in degrees."""132pass133134135class WaitHeadingTimeout(AutoTestTimeoutException):136"""Thrown when fails to achieve given heading."""137pass138139140class WaitDistanceTimeout(AutoTestTimeoutException):141"""Thrown when fails to attain distance"""142pass143144145class WaitLocationTimeout(AutoTestTimeoutException):146"""Thrown when fails to attain location"""147pass148149150class WaitWaypointTimeout(AutoTestTimeoutException):151"""Thrown when fails to attain waypoint ranges"""152pass153154155class SetRCTimeout(AutoTestTimeoutException):156"""Thrown when fails to send RC commands"""157pass158159160class MsgRcvTimeoutException(AutoTestTimeoutException):161"""Thrown when fails to receive an expected message"""162pass163164165class NotAchievedException(ErrorException):166"""Thrown when fails to achieve a goal"""167pass168169170class OldpymavlinkException(ErrorException):171"""Thrown when a new feature is required from pymavlink"""172pass173174175class YawSpeedNotAchievedException(NotAchievedException):176"""Thrown when fails to achieve given yaw speed."""177pass178179180class SpeedVectorNotAchievedException(NotAchievedException):181"""Thrown when fails to achieve given speed vector."""182pass183184185class PreconditionFailedException(ErrorException):186"""Thrown when a precondition for a test is not met"""187pass188189190class ArmedAtEndOfTestException(ErrorException):191"""Created when test left vehicle armed"""192pass193194195class Context(object):196def __init__(self):197self.parameters = []198self.sitl_commandline_customised = False199self.reboot_sitl_was_done = False200self.message_hooks = []201self.collections = {}202self.heartbeat_interval_ms = 1000203self.original_heartbeat_interval_ms = None204self.installed_scripts = []205self.installed_modules = []206self.overridden_message_rates = {}207self.raising_debug_trap_on_exceptions = False208209210# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python211class TeeBoth(object):212def __init__(self, name, mode, mavproxy_logfile, suppress_stdout=False):213self.suppress_stdout = suppress_stdout214self.file = open(name, mode)215self.stdout = sys.stdout216self.stderr = sys.stderr217self.mavproxy_logfile = mavproxy_logfile218self.mavproxy_logfile.set_fh(self)219sys.stdout = self220sys.stderr = self221222def close(self):223sys.stdout = self.stdout224sys.stderr = self.stderr225self.mavproxy_logfile.set_fh(None)226self.mavproxy_logfile = None227self.file.close()228self.file = None229230def write(self, data):231if isinstance(data, bytes):232data = data.decode('ascii')233self.file.write(data)234if not self.suppress_stdout:235self.stdout.write(data)236237def flush(self):238self.file.flush()239240241class MAVProxyLogFile(object):242def __init__(self):243self.fh = None244245def close(self):246pass247248def set_fh(self, fh):249self.fh = fh250251def write(self, data):252if self.fh is not None:253self.fh.write(data)254else:255sys.stdout.write(data)256257def flush(self):258if self.fh is not None:259self.fh.flush()260else:261sys.stdout.flush()262263264class Telem(object):265def __init__(self, destination_address, progress_function=None, verbose=False):266self.destination_address = destination_address267self.progress_function = progress_function268self.verbose = verbose269270self.buffer = bytes()271self.connected = False272self.port = None273self.progress_log = ""274275def progress(self, message):276message = "%s: %s" % (self.progress_tag(), message)277if self.progress_function is not None:278self.progress_function(message)279return280if not self.verbose:281self.progress_log += message282return283print(message)284285def connect(self):286try:287self.connected = False288self.progress("Connecting to (%s:%u)" % self.destination_address)289if self.port is not None:290try:291self.port.close() # might be reopening292except Exception:293pass294self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)295self.port.connect(self.destination_address)296self.port.setblocking(False)297self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)298self.connected = True299self.progress("Connected")300except IOError as e:301self.progress("Failed to connect: %s" % str(e))302time.sleep(0.5)303return False304return True305306def do_read(self) -> bytes:307try:308data = self.port.recv(1024)309except socket.error as e:310if e.errno not in [errno.EAGAIN, errno.EWOULDBLOCK]:311self.progress("Exception: %s" % str(e))312self.connected = False313return bytes()314if len(data) == 0:315self.progress("EOF")316self.connected = False317return bytes()318# print(f"Read {len(data)=} bytes {type(data)=}")319return data320321def do_write(self, some_bytes):322try:323written = self.port.send(some_bytes)324except socket.error as e:325if e.errno in [errno.EAGAIN, errno.EWOULDBLOCK]:326return 0327self.progress("Exception: %s" % str(e))328raise329if written != len(some_bytes):330raise ValueError("Short write")331332def update(self):333if not self.connected:334if not self.connect():335return336return self.update_read()337338339class IBusMessage(object):340def checksum_bytes(self, out):341checksum = 0xFFFF342for b in iter(out):343checksum -= b344return checksum345346347class IBusResponse(IBusMessage):348def __init__(self, some_bytes):349self.len = some_bytes[0]350checksum = self.checksum_bytes(some_bytes[:self.len-2])351if checksum >> 8 != some_bytes[self.len-1]:352raise ValueError("Checksum bad (-1)")353if checksum & 0xff != some_bytes[self.len-2]:354raise ValueError("Checksum bad (-2)")355self.address = some_bytes[1] & 0x0F356self.handle_payload_bytes(some_bytes[2:self.len-2])357358359class IBusResponse_DISCOVER(IBusResponse):360def handle_payload_bytes(self, payload_bytes):361if len(payload_bytes):362raise ValueError("Not expecting payload bytes (%u)" %363(len(payload_bytes), ))364365366class IBusResponse_GET_SENSOR_TYPE(IBusResponse):367def handle_payload_bytes(self, payload_bytes):368if len(payload_bytes) != 2:369raise ValueError("Expected 2 payload bytes")370self.sensor_type = payload_bytes[0]371self.sensor_length = payload_bytes[1]372373374class IBusResponse_GET_SENSOR_VALUE(IBusResponse):375def handle_payload_bytes(self, payload_bytes):376self.sensor_value = payload_bytes377378def get_sensor_value(self):379'''returns an integer based off content'''380ret = 0381for i in range(len(self.sensor_value)):382x = self.sensor_value[i]383ret = ret | (x << (i*8))384return ret385386387class IBusRequest(IBusMessage):388def __init__(self, command, address):389self.command = command390self.address = address391392def payload_bytes(self):393'''most requests don't have a payload'''394return bytearray()395396def for_wire(self):397out = bytearray()398payload_bytes = self.payload_bytes()399payload_length = len(payload_bytes)400length = 1 + 1 + payload_length + 2 # len+cmd|adr+payloadlen+cksum401format_string = '<BB' + ('B' * payload_length)402out.extend(struct.pack(format_string,403length,404(self.command << 4) | self.address,405*payload_bytes,406))407checksum = self.checksum_bytes(out)408out.extend(struct.pack("<BB", checksum & 0xff, checksum >> 8))409return out410411412class IBusRequest_DISCOVER(IBusRequest):413def __init__(self, address):414super(IBusRequest_DISCOVER, self).__init__(0x08, address)415416417class IBusRequest_GET_SENSOR_TYPE(IBusRequest):418def __init__(self, address):419super(IBusRequest_GET_SENSOR_TYPE, self).__init__(0x09, address)420421422class IBusRequest_GET_SENSOR_VALUE(IBusRequest):423def __init__(self, address):424super(IBusRequest_GET_SENSOR_VALUE, self).__init__(0x0A, address)425426427class IBus(Telem):428def __init__(self, destination_address):429super(IBus, self).__init__(destination_address)430431def progress_tag(self):432return "IBus"433434def packet_from_buffer(self, buffer):435t = buffer[1] >> 4436if t == 0x08:437return IBusResponse_DISCOVER(buffer)438if t == 0x09:439return IBusResponse_GET_SENSOR_TYPE(buffer)440if t == 0x0A:441return IBusResponse_GET_SENSOR_VALUE(buffer)442raise ValueError("Unknown response type (%u)" % t)443444def update_read(self):445self.buffer += self.do_read()446while len(self.buffer):447msglen = self.buffer[0]448if len(self.buffer) < msglen:449return450packet = self.packet_from_buffer(self.buffer[:msglen])451self.buffer = self.buffer[msglen:]452return packet453454455class WaitAndMaintain(object):456def __init__(self,457test_suite,458minimum_duration=None,459progress_print_interval=1,460timeout=30,461epsilon=None,462comparator=None,463fn=None,464fn_interval=None,465):466self.test_suite = test_suite467self.minimum_duration = minimum_duration468self.achieving_duration_start = None469self.timeout = timeout470self.epsilon = epsilon471self.last_progress_print = 0472self.progress_print_interval = progress_print_interval473self.comparator = comparator474if self.minimum_duration is not None:475if self.timeout < self.minimum_duration:476raise ValueError("timeout less than min duration")477478self.fn = fn479self.fn_interval = fn_interval480self.last_fn_run_time = 0481482def run(self):483self.announce_test_start()484485tstart = self.test_suite.get_sim_time_cached()486while True:487now = self.test_suite.get_sim_time_cached()488current_value = self.get_current_value()489if now - self.last_progress_print > self.progress_print_interval:490self.print_progress(now, current_value)491self.last_progress_print = now492493# check for timeout494if now - tstart > self.timeout:495self.print_failure_text(now, current_value)496raise self.timeoutexception()497498# call supplied function if appropriate:499if (self.fn is not None and500now - self.last_fn_run_time > self.fn_interval):501self.fn()502self.last_fn_run_time = now503504# handle the case where we are are achieving our value:505if self.validate_value(current_value):506if self.achieving_duration_start is None:507self.achieving_duration_start = now508if (self.minimum_duration is None or509now - self.achieving_duration_start > self.minimum_duration):510self.announce_success()511return True512continue513514# handle the case where we are not achieving our value:515self.achieving_duration_start = None516517def progress(self, text):518self.test_suite.progress(text)519520def announce_test_start(self):521self.progress(self.announce_start_text())522523def announce_success(self):524self.progress(self.success_text())525526def print_progress(self, now, value):527text = self.progress_text(value)528if self.achieving_duration_start is not None:529delta = now - self.achieving_duration_start530text += f" (maintain={delta:.1f}/{self.minimum_duration})"531self.progress(text)532533def print_failure_text(self, now, value):534'''optionally print a more detailed error string'''535pass536537def progress_text(self, value):538return f"want={self.get_target_value()} got={value}"539540def validate_value(self, value):541target_value = self.get_target_value()542if self.comparator is not None:543return self.comparator(value, target_value)544545if self.epsilon is not None:546return (abs(value - target_value) <= self.epsilon)547548return value == target_value549550def timeoutexception(self):551return AutoTestTimeoutException("Failed to attain or maintain value")552553def success_text(self):554return f"{type(self)} Success"555556557class WaitAndMaintainLocation(WaitAndMaintain):558def __init__(self, test_suite, target, accuracy=5, height_accuracy=1, **kwargs):559super(WaitAndMaintainLocation, self).__init__(test_suite, **kwargs)560self.target = target561self.height_accuracy = height_accuracy562self.accuracy = accuracy563564def announce_start_text(self):565t = self.target566if self.height_accuracy is not None:567return ("Waiting for distance to Location (%.4f, %.4f, %.2f) (h_err<%f, v_err<%.2f " %568(t.lat, t.lng, t.alt*0.01, self.accuracy, self.height_accuracy))569return ("Waiting for distance to Location (%.4f, %.4f) (h_err<%f" %570(t.lat, t.lng, self.accuracy))571572def get_target_value(self):573return self.loc574575def get_current_value(self):576return self.test_suite.mav.location()577578def horizontal_error(self, value):579return self.test_suite.get_distance(value, self.target)580581def vertical_error(self, value):582return math.fabs(value.alt*0.01 - self.target.alt*0.01)583584def validate_value(self, value):585if self.horizontal_error(value) > self.accuracy:586return False587588if self.height_accuracy is None:589return True590591if self.vertical_error(value) > self.height_accuracy:592return False593594return True595596def success_text(self):597return "Reached location"598599def timeoutexception(self):600return AutoTestTimeoutException("Failed to attain location")601602def progress_text(self, current_value):603if self.height_accuracy is not None:604return (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}") # noqa605606return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}")607608609class WaitAndMaintainEKFFlags(WaitAndMaintain):610'''Waits for EKF status flags to include required_flags and have611error_bits *not* set.'''612def __init__(self, test_suite, required_flags, error_bits, **kwargs):613super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs)614self.required_flags = required_flags615self.error_bits = error_bits616self.last_EKF_STATUS_REPORT = None617618def announce_start_text(self):619return f"Waiting for EKF value {self.required_flags}"620621def get_current_value(self):622self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10)623return self.last_EKF_STATUS_REPORT.flags624625def validate_value(self, value):626if value & self.error_bits:627return False628629if (value & self.required_flags) != self.required_flags:630return False631632return True633634def success_text(self):635return "EKF Flags OK"636637def timeoutexception(self):638self.progress("Last EKF status report:")639self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT))640641return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}")642643def progress_text(self, current_value):644error_bits = current_value & self.error_bits645return (f"Want={self.required_flags} got={current_value} errors={error_bits}")646647def ekf_flags_string(self, bits):648ret = []649for i in range(0, 16):650bit = 1 << i651try:652if not bits & bit:653continue654name = mavutil.mavlink.enums["ESTIMATOR_STATUS_FLAGS"][bit].name655trimmed_name = name.removeprefix("ESTIMATOR_")656ret.append(trimmed_name)657except KeyError:658ret.append(str(bit))659return "|".join(ret)660661def failure_text(self, now, current_value):662components = []663components.append(("want", self.ekf_flags_string(self.required_flags)))664665missing_bits = self.required_flags & ~current_value666if missing_bits:667components.append(("missing", self.ekf_flags_string(missing_bits)))668669error_bits = current_value & self.error_bits670if error_bits:671components.append(("errors", self.ekf_flags_string(error_bits)))672673return " ".join([f"{n}={v}" for (n, v) in components])674675def print_failure_text(self, now, current_value):676self.progress(self.failure_text(now, current_value))677678679class WaitAndMaintainArmed(WaitAndMaintain):680def get_current_value(self):681return self.test_suite.armed()682683def get_target_value(self):684return True685686def announce_start_text(self):687return "Ensuring vehicle remains armed"688689690class WaitAndMaintainDisarmed(WaitAndMaintain):691def get_current_value(self):692return self.test_suite.armed()693694def get_target_value(self):695return False696697def announce_start_text(self):698return "Ensuring vehicle remains disarmed"699700701class WaitAndMaintainServoChannelValue(WaitAndMaintain):702def __init__(self, test_suite, channel, value, **kwargs):703super(WaitAndMaintainServoChannelValue, self).__init__(test_suite, **kwargs)704self.channel = channel705self.value = value706707def announce_start_text(self):708str_operator = ""709if self.comparator == operator.lt:710str_operator = "less than "711elif self.comparator == operator.gt:712str_operator = "more than "713714return f"Waiting for SERVO_OUTPUT_RAW.servo{self.channel}_value value {str_operator}{self.value}"715716def get_target_value(self):717return self.value718719def get_current_value(self):720m = self.test_suite.assert_receive_message('SERVO_OUTPUT_RAW', timeout=10)721channel_field = "servo%u_raw" % self.channel722m_value = getattr(m, channel_field, None)723if m_value is None:724raise ValueError(f"message ({str(m)}) has no field {channel_field}")725726self.last_SERVO_OUTPUT_RAW = m727return m_value728729730class WaitAndMaintainAttitude(WaitAndMaintain):731def __init__(self, test_suite, desroll=None, despitch=None, **kwargs):732super().__init__(test_suite, **kwargs)733self.desroll = desroll734self.despitch = despitch735736if self.desroll is None and self.despitch is None:737raise ValueError("despitch or desroll must be supplied")738739def announce_start_text(self):740conditions = []741if self.desroll is not None:742conditions.append(f"roll={self.desroll}")743if self.despitch is not None:744conditions.append(f"pitch={self.despitch}")745746return f"Waiting for {' and '.join(conditions)}"747748def get_target_value(self):749return (self.desroll, self.despitch)750751def get_current_value(self):752m = self.test_suite.assert_receive_message('ATTITUDE', timeout=10)753self.last_ATTITUDE = m754return (math.degrees(m.roll), math.degrees(m.pitch))755756def validate_value(self, value):757(candidate_roll, candidate_pitch) = value758759if self.desroll is not None:760roll_error = abs(self.desroll - candidate_roll)761if roll_error > self.epsilon:762return False763764if self.despitch is not None:765pitch_error = abs(self.despitch - candidate_pitch)766if pitch_error > self.epsilon:767return False768769return True770771def success_text(self):772return "Attained attitude"773774def timeoutexception(self):775return AutoTestTimeoutException("Failed to attain attitude")776777def progress_text(self, current_value):778(achieved_roll, achieved_pitch) = current_value779axis_progress = []780781if self.desroll is not None:782axis_progress.append(f"r={achieved_roll: >8.3f} des-r={self.desroll}")783784if self.despitch is not None:785axis_progress.append(f"p={achieved_pitch: >8.3f} des-p={self.despitch}")786787return " ".join(axis_progress)788789790class MSP_Generic(Telem):791def __init__(self, destination_address):792super(MSP_Generic, self).__init__(destination_address)793794self.callback = None795796self.STATE_IDLE = "IDLE"797self.STATE_WANT_HEADER_DOLLARS = "WANT_DOLLARS"798self.STATE_WANT_HEADER_M = "WANT_M"799self.STATE_WANT_HEADER_GT = "WANT_GT"800self.STATE_WANT_DATA_SIZE = "WANT_DATA_SIZE"801self.STATE_WANT_COMMAND = "WANT_COMMAND"802self.STATE_WANT_DATA = "WANT_DATA"803self.STATE_WANT_CHECKSUM = "WANT_CHECKSUM"804805self.state = self.STATE_IDLE806807def progress(self, message):808print("MSP: %s" % message)809810def set_state(self, state):811# self.progress("Moving to state (%s)" % state)812self.state = state813814def init_checksum(self, b):815self.checksum = 0816self.add_to_checksum(b)817818def add_to_checksum(self, b):819self.checksum ^= (b & 0xFF)820821def process_command(self, cmd, data):822if self.callback is not None:823self.callback(cmd, data)824else:825print("cmd=%s" % str(cmd))826827def update_read(self):828for byte in self.do_read():829c = chr(byte)830# print("Got (0x%02x) (%s) (%s) state=%s" % (byte, chr(byte), str(type(byte)), self.state))831if self.state == self.STATE_IDLE:832# reset state833self.set_state(self.STATE_WANT_HEADER_DOLLARS)834# deliberate fallthrough right here835if self.state == self.STATE_WANT_HEADER_DOLLARS:836if c == '$':837self.set_state(self.STATE_WANT_HEADER_M)838continue839if self.state == self.STATE_WANT_HEADER_M:840if c != 'M':841raise Exception("Malformed packet")842self.set_state(self.STATE_WANT_HEADER_GT)843continue844if self.state == self.STATE_WANT_HEADER_GT:845if c != '>':846raise Exception("Malformed packet")847self.set_state(self.STATE_WANT_DATA_SIZE)848continue849if self.state == self.STATE_WANT_DATA_SIZE:850self.data_size = byte851self.set_state(self.STATE_WANT_COMMAND)852self.data = bytearray()853self.checksum = 0854self.add_to_checksum(byte)855continue856if self.state == self.STATE_WANT_COMMAND:857self.command = byte858self.add_to_checksum(byte)859if self.data_size != 0:860self.set_state(self.STATE_WANT_DATA)861else:862self.set_state(self.STATE_WANT_CHECKSUM)863continue864if self.state == self.STATE_WANT_DATA:865self.add_to_checksum(byte)866self.data.append(byte)867if len(self.data) == self.data_size:868self.set_state(self.STATE_WANT_CHECKSUM)869continue870if self.state == self.STATE_WANT_CHECKSUM:871if self.checksum != byte:872raise Exception("Checksum fail (want=0x%02x calced=0x%02x" %873(byte, self.checksum))874self.process_command(self.command, self.data)875self.set_state(self.STATE_IDLE)876877878class MSP_DJI(MSP_Generic):879FRAME_GPS_RAW = 106880FRAME_ATTITUDE = 108881882def __init__(self, destination_address):883super(MSP_DJI, self).__init__(destination_address)884self.callback = self.command_callback885self.frames = {}886887class Frame(object):888def __init__(self, data):889self.data = data890891def intn(self, offset, count):892ret = 0893for i in range(offset, offset+count):894ret = ret | (ord(self.data[i]) << ((i-offset)*8))895return ret896897def int32(self, offset):898t = struct.unpack("<i", self.data[offset:offset+4])899return t[0]900901def int16(self, offset):902t = struct.unpack("<h", self.data[offset:offset+2])903return t[0]904905class FrameATTITUDE(Frame):906def roll(self):907'''roll in degrees'''908return self.int16(0) * 10909910def pitch(self):911'''pitch in degrees'''912return self.int16(2) * 10913914def yaw(self):915'''yaw in degrees'''916return self.int16(4)917918class FrameGPS_RAW(Frame):919'''see gps_state_s'''920def fix_type(self):921return self.uint8(0)922923def num_sats(self):924return self.uint8(1)925926def lat(self):927return self.int32(2) / 1e7928929def lon(self):930return self.int32(6) / 1e7931932def LocationInt(self):933# other fields are available, I'm just lazy934return LocationInt(self.int32(2), self.int32(6), 0, 0)935936def command_callback(self, frametype, data):937# print("X: %s %s" % (str(frametype), str(data)))938if frametype == MSP_DJI.FRAME_ATTITUDE:939frame = MSP_DJI.FrameATTITUDE(data)940elif frametype == MSP_DJI.FRAME_GPS_RAW:941frame = MSP_DJI.FrameGPS_RAW(data)942else:943return944self.frames[frametype] = frame945946def get_frame(self, frametype):947return self.frames[frametype]948949950class LTM(Telem):951def __init__(self, destination_address):952super(LTM, self).__init__(destination_address)953954self.HEADER1 = 0x24955self.HEADER2 = 0x54956957self.FRAME_G = 0x47958self.FRAME_A = 0x41959self.FRAME_S = 0x53960961self.frame_lengths = {962self.FRAME_G: 18,963self.FRAME_A: 10,964self.FRAME_S: 11,965}966self.frame_lengths = {967self.FRAME_G: 18,968self.FRAME_A: 10,969self.FRAME_S: 11,970}971972self.data_by_id = {}973self.frames = {}974975def g(self):976return self.frames.get(self.FRAME_G, None)977978def a(self):979return self.frames.get(self.FRAME_A, None)980981def s(self):982return self.frames.get(self.FRAME_S, None)983984def progress_tag(self):985return "LTM"986987def handle_data(self, dataid, value):988self.progress("%u=%u" % (dataid, value))989self.data_by_id[dataid] = value990991def consume_frame(self):992b2 = self.buffer[2]993frame_type = b2994frame_length = self.frame_lengths[frame_type]995# check frame CRC996crc = 0997count = 0998for c in self.buffer[3:frame_length-1]:999crc ^= c1000count += 11001buffer_crc = self.buffer[frame_length-1]1002if crc != buffer_crc:1003raise NotAchievedException("Invalid checksum on frame type %s" % str(chr(frame_type)))1004# self.progress("Received valid %s frame" % str(chr(frame_type)))10051006class Frame(object):1007def __init__(self, buffer):1008self.buffer = buffer10091010def intn(self, offset, count):1011ret = 01012for i in range(offset, offset+count):1013ret = ret | (ord(self.buffer[i]) << ((i-offset)*8))1014return ret10151016def int32(self, offset):1017t = struct.unpack("<i", self.buffer[offset:offset+4])1018return t[0]1019# return self.intn(offset, 4)10201021def int16(self, offset):1022t = struct.unpack("<h", self.buffer[offset:offset+2])1023return t[0]1024# return self.intn(offset, 2)10251026class FrameG(Frame):1027def __init__(self, buffer):1028super(FrameG, self,).__init__(buffer)10291030def lat(self):1031return self.int32(3)10321033def lon(self):1034return self.int32(7)10351036def gndspeed(self):1037return self.buffer[11]10381039def alt(self):1040return self.int32(12)10411042def sats(self):1043s = self.buffer[16]1044return (s >> 2)10451046def fix_type(self):1047s = self.buffer[16]1048return s & 0b1110491050class FrameA(Frame):1051def __init__(self, buffer):1052super(FrameA, self,).__init__(buffer)10531054def pitch(self):1055return self.int16(3)10561057def roll(self):1058return self.int16(5)10591060def hdg(self):1061return self.int16(7)10621063class FrameS(Frame):1064def __init__(self, buffer):1065super(FrameS, self,).__init__(buffer)10661067if frame_type == self.FRAME_G:1068frame = FrameG(self.buffer[0:frame_length-1])1069elif frame_type == self.FRAME_A:1070frame = FrameA(self.buffer[0:frame_length-1])1071elif frame_type == self.FRAME_S:1072frame = FrameS(self.buffer[0:frame_length-1])1073else:1074raise NotAchievedException("Bad frame?!?!?!")1075self.buffer = self.buffer[frame_length:]1076self.frames[frame_type] = frame10771078def update_read(self):1079self.buffer += self.do_read()1080while len(self.buffer):1081if len(self.buffer) == 0:1082break1083b0 = self.buffer[0]1084if b0 != self.HEADER1:1085self.bad_chars += 11086self.buffer = self.buffer[1:]1087continue1088b1 = self.buffer[1]1089if b1 != self.HEADER2:1090self.bad_chars += 11091self.buffer = self.buffer[1:]1092continue1093b2 = self.buffer[2]1094if b2 not in [self.FRAME_G, self.FRAME_A, self.FRAME_S]:1095self.bad_chars += 11096self.buffer = self.buffer[1:]1097continue1098frame_len = self.frame_lengths[b2]1099if len(self.buffer) < frame_len:1100continue1101self.consume_frame()11021103def get_data(self, dataid):1104try:1105return self.data_by_id[dataid]1106except KeyError:1107pass1108return None110911101111class CRSF(Telem):1112def __init__(self, destination_address):1113super(CRSF, self).__init__(destination_address)11141115self.dataid_vtx_frame = 01116self.dataid_vtx_telem = 11117self.dataid_vtx_unknown = 211181119self.data_id_map = {1120self.dataid_vtx_frame: bytearray([0xC8, 0x8, 0xF, 0xCE, 0x30, 0x8, 0x16, 0xE9, 0x0, 0x5F]),1121self.dataid_vtx_telem: bytearray([0xC8, 0x7, 0x10, 0xCE, 0xE, 0x16, 0x65, 0x0, 0x1B]),1122self.dataid_vtx_unknown: bytearray([0xC8, 0x9, 0x8, 0x0, 0x9E, 0x0, 0x0, 0x0, 0x0, 0x0, 0x95]),1123}11241125def write_data_id(self, dataid):1126self.do_write(self.data_id_map[dataid])11271128def progress_tag(self):1129return "CRSF"113011311132class DEVO(Telem):1133def __init__(self, destination_address):1134super(DEVO, self).__init__(destination_address)11351136self.HEADER = 0xAA1137self.frame_length = 2011381139# frame is 'None' until we receive a frame with VALID header and checksum1140self.frame = None1141self.bad_chars = 011421143def progress_tag(self):1144return "DEVO"11451146def consume_frame(self):1147# check frame checksum1148checksum = 01149for c in self.buffer[:self.frame_length-1]:1150checksum += c1151checksum &= 0xff # since we receive 8 bit checksum1152buffer_checksum = self.buffer[self.frame_length-1]1153if checksum != buffer_checksum:1154raise NotAchievedException("Invalid checksum")11551156class FRAME(object):1157def __init__(self, buffer):1158self.buffer = buffer11591160def int32(self, offset):1161t = struct.unpack("<i", self.buffer[offset:offset+4])1162return t[0]11631164def int16(self, offset):1165t = struct.unpack("<h", self.buffer[offset:offset+2])1166return t[0]11671168def lon(self):1169return self.int32(1)11701171def lat(self):1172return self.int32(5)11731174def alt(self):1175return self.int32(9)11761177def speed(self):1178return self.int16(13)11791180def temp(self):1181return self.int16(15)11821183def volt(self):1184return self.int16(17)11851186self.frame = FRAME(self.buffer[0:self.frame_length-1])1187self.buffer = self.buffer[self.frame_length:]11881189def update_read(self):1190self.buffer += self.do_read()1191while len(self.buffer):1192if len(self.buffer) == 0:1193break1194b0 = self.buffer[0]1195if b0 != self.HEADER:1196self.bad_chars += 11197self.buffer = self.buffer[1:]1198continue1199if len(self.buffer) < self.frame_length:1200continue1201self.consume_frame()120212031204class FRSky(Telem):1205def __init__(self, destination_address, verbose=False):1206super(FRSky, self).__init__(destination_address, verbose=verbose)12071208self.dataid_GPS_ALT_BP = 0x011209self.dataid_TEMP1 = 0x021210self.dataid_FUEL = 0x041211self.dataid_TEMP2 = 0x051212self.dataid_GPS_ALT_AP = 0x091213self.dataid_BARO_ALT_BP = 0x101214self.dataid_GPS_SPEED_BP = 0x111215self.dataid_GPS_LONG_BP = 0x121216self.dataid_GPS_LAT_BP = 0x131217self.dataid_GPS_COURS_BP = 0x141218self.dataid_GPS_SPEED_AP = 0x191219self.dataid_GPS_LONG_AP = 0x1A1220self.dataid_GPS_LAT_AP = 0x1B1221self.dataid_BARO_ALT_AP = 0x211222self.dataid_GPS_LONG_EW = 0x221223self.dataid_GPS_LAT_NS = 0x231224self.dataid_CURRENT = 0x281225self.dataid_VFAS = 0x39122612271228class FRSkyD(FRSky):1229def __init__(self, destination_address):1230super(FRSkyD, self).__init__(destination_address)12311232self.state_WANT_START_STOP_D = 16,1233self.state_WANT_ID = 171234self.state_WANT_BYTE1 = 181235self.state_WANT_BYTE2 = 1912361237self.START_STOP_D = 0x5E1238self.BYTESTUFF_D = 0x5D12391240self.state = self.state_WANT_START_STOP_D12411242self.data_by_id = {}1243self.bad_chars = 012441245def progress_tag(self):1246return "FRSkyD"12471248def handle_data(self, dataid, value):1249self.progress("%u=%u" % (dataid, value))1250self.data_by_id[dataid] = value12511252def update_read(self):1253self.buffer += self.do_read()1254consume = None1255while len(self.buffer):1256if consume is not None:1257self.buffer = self.buffer[consume:]1258if len(self.buffer) == 0:1259break1260consume = 11261b = self.buffer[0]1262if self.state == self.state_WANT_START_STOP_D:1263if b != self.START_STOP_D:1264# we may come into a stream mid-way, so we can't judge1265self.bad_chars += 11266continue1267self.state = self.state_WANT_ID1268continue1269elif self.state == self.state_WANT_ID:1270self.dataid = b1271self.state = self.state_WANT_BYTE11272continue1273elif self.state in [self.state_WANT_BYTE1, self.state_WANT_BYTE2]:1274if b == 0x5D:1275# byte-stuffed1276if len(self.buffer) < 2:1277# try again in a little while1278consume = 01279return1280if self.buffer[1] == 0x3E:1281b = self.START_STOP_D1282elif self.buffer[1] == 0x3D:1283b = self.BYTESTUFF_D1284else:1285raise ValueError("Unknown stuffed byte")1286consume = 21287if self.state == self.state_WANT_BYTE1:1288self.b1 = b1289self.state = self.state_WANT_BYTE21290continue12911292data = self.b1 | b << 81293self.handle_data(self.dataid, data)1294self.state = self.state_WANT_START_STOP_D12951296def get_data(self, dataid):1297try:1298return self.data_by_id[dataid]1299except KeyError:1300pass1301return None130213031304class SPortPacket(object):1305def __init__(self):1306self.START_STOP_SPORT = 0x7E1307self.BYTESTUFF_SPORT = 0x7D130813091310class SPortUplinkPacket(SPortPacket):1311def __init__(self, appid0, appid1, data0, data1, data2, data3):1312super(SPortUplinkPacket, self).__init__()1313self.appid0 = appid01314self.appid1 = appid11315self.data0 = data01316self.data1 = data11317self.data2 = data21318self.data3 = data31319self.SENSOR_ID_UPLINK_ID = 0x0D1320self.SPORT_UPLINK_FRAME = 0x301321self.uplink_id = self.SENSOR_ID_UPLINK_ID1322self.frame = self.SPORT_UPLINK_FRAME13231324def packed(self):1325return struct.pack(1326'<BBBBBBBB',1327self.uplink_id,1328self.frame,1329self.appid0 & 0xff,1330self.appid1 & 0xff,1331self.data0 & 0xff,1332self.data1 & 0xff,1333self.data2 & 0xff,1334self.data3 & 0xff,1335)13361337def update_checksum(self, byte):1338self.checksum += byte1339self.checksum += self.checksum >> 81340self.checksum &= 0xFF13411342def checksum(self):1343self.checksum = 01344self.update_checksum(self.frame & 0xff)1345self.update_checksum(self.appid0 & 0xff)1346self.update_checksum(self.appid1 & 0xff)1347self.update_checksum(self.data0 & 0xff)1348self.update_checksum(self.data1 & 0xff)1349self.update_checksum(self.data2 & 0xff)1350self.update_checksum(self.data3 & 0xff)1351self.checksum = 0xff - ((self.checksum & 0xff) + (self.checksum >> 8))1352return self.checksum & 0xff13531354def for_wire(self):1355out = bytearray()1356out.extend(self.packed())1357out.extend(struct.pack('<B', self.checksum()))1358stuffed = bytearray()1359stuffed.extend(struct.pack('<B', self.START_STOP_SPORT))1360for pbyte in out:1361if pbyte in [self.BYTESTUFF_SPORT,1362self.START_STOP_SPORT]:1363# bytestuff1364stuffed.append(self.BYTESTUFF_SPORT)1365stuffed.append(pbyte ^ self.SPORT_FRAME_XOR)1366else:1367stuffed.append(pbyte)1368return stuffed136913701371class SPortPollPacket(SPortPacket):1372def __init__(self, sensor):1373super(SPortPollPacket, self).__init__()1374self.sensor = sensor13751376def for_wire(self):1377return struct.pack(1378'<BB',1379self.START_STOP_SPORT,1380self.sensor & 0xff,1381)138213831384class MAVliteMessage(object):1385def __init__(self, msgid, body):1386self.msgid = msgid1387self.body = body1388self.SENSOR_ID_UPLINK_ID = 0x0D1389self.SPORT_UPLINK_FRAME = 0x3013901391def checksum_bytes(self, some_bytes):1392checksum = 01393for b in some_bytes:1394checksum += b1395checksum += checksum >> 81396checksum &= 0xFF1397return checksum13981399def to_sport_packets(self):1400ret = []1401all_bytes = bytearray([len(self.body), self.msgid])1402all_bytes.extend(self.body)14031404# insert sequence numbers:1405seq = 01406sequenced = bytearray()1407while len(all_bytes):1408chunk = all_bytes[0:5]1409all_bytes = all_bytes[5:]1410sequenced.append(seq)1411sequenced.extend(chunk)1412seq += 114131414# we may need another sport packet just for the checksum:1415if len(sequenced) % 6 == 0:1416sequenced.append(seq)1417seq += 114181419checksum = self.checksum_bytes(sequenced)1420sequenced.append(checksum)14211422while len(sequenced):1423chunk = sequenced[0:6]1424sequenced = sequenced[6:]1425chunk.extend([0] * (6-len(chunk))) # pad to 61426packet = SPortUplinkPacket(1427*chunk1428)1429ret.append(packet)1430return ret143114321433class SPortToMAVlite(object):1434def __init__(self):1435self.state_WANT_LEN = "want len"1436self.state_WANT_MSGID = "want msgid"1437self.state_WANT_PAYLOAD = "want payload"1438self.state_WANT_CHECKSUM = "want checksum"1439self.state_MESSAGE_RECEIVED = "message received"14401441self.reset()14421443def progress(self, message):1444print("SPortToMAVLite: %s" % message)14451446def reset(self):1447self.want_seq = 01448self.all_bytes = bytearray()1449self.payload = bytearray()1450self.state = self.state_WANT_LEN14511452def checksum_bytes(self, some_bytes):1453checksum = 01454for b in some_bytes:1455checksum += b1456checksum += checksum >> 81457checksum &= 0xFF1458return checksum14591460def downlink_handler(self, some_bytes):1461'''adds some_bytes into a mavlite message'''1462if some_bytes[0] == 0x00:1463self.reset()1464if some_bytes[0] != self.want_seq:1465raise NotAchievedException("Unexpected seqno; want=%u got=%u" %1466(self.want_seq, some_bytes[0]))1467self.all_bytes.append(some_bytes[0])1468self.want_seq += 11469for byte in some_bytes[1:]:1470if self.state == self.state_WANT_LEN:1471self.payload_len = byte1472self.all_bytes.append(byte)1473self.state = self.state_WANT_MSGID1474continue1475if self.state == self.state_WANT_MSGID:1476self.msgid = byte1477self.all_bytes.append(byte)1478if self.payload_len == 0:1479self.state = self.state_WANT_CHECKSUM1480else:1481self.state = self.state_WANT_PAYLOAD1482continue1483if self.state == self.state_WANT_PAYLOAD:1484self.payload.append(byte)1485self.all_bytes.append(byte)1486if len(self.payload) == self.payload_len:1487self.state = self.state_WANT_CHECKSUM1488continue1489if self.state == self.state_WANT_CHECKSUM:1490calculated_checksum = self.checksum_bytes(self.all_bytes)1491if calculated_checksum != byte:1492raise Exception("Checksum failure (calc=%u) (recv=%u)" % (calculated_checksum, byte))1493self.state = self.state_MESSAGE_RECEIVED1494break14951496def get_message(self):1497if self.state != self.state_MESSAGE_RECEIVED:1498raise Exception("Wrong state")1499return MAVliteMessage(self.msgid, self.payload)150015011502class FRSkySPort(FRSky):1503def __init__(self, destination_address, verbose=True, get_time=time.time):1504super(FRSkySPort, self).__init__(1505destination_address,1506verbose=verbose1507)15081509self.get_time = get_time15101511self.state_SEND_POLL = "sendpoll"1512self.state_WANT_FRAME_TYPE = "want_frame_type"1513self.state_WANT_ID1 = "want_id1"1514self.state_WANT_ID2 = "want id2"1515self.state_WANT_DATA = "want data"1516self.state_WANT_CRC = "want crc"15171518self.START_STOP_SPORT = 0x7E1519self.BYTESTUFF_SPORT = 0x7D1520self.SPORT_DATA_FRAME = 0x101521self.SPORT_DOWNLINK_FRAME = 0x321522self.SPORT_FRAME_XOR = 0x2015231524self.SENSOR_ID_VARIO = 0x00 # Sensor ID 01525self.SENSOR_ID_FAS = 0x22 # Sensor ID 21526self.SENSOR_ID_GPS = 0x83 # Sensor ID 31527self.SENSOR_ID_RPM = 0xE4 # Sensor ID 41528self.SENSOR_ID_SP2UR = 0xC6 # Sensor ID 61529self.SENSOR_ID_27 = 0x1B # Sensor ID 2715301531# MAVlite support:1532self.SENSOR_ID_DOWNLINK1_ID = 0x341533self.SENSOR_ID_DOWNLINK2_ID = 0x671534self.SENSOR_ID_UPLINK_ID = 0x0D15351536self.state = self.state_WANT_FRAME_TYPE15371538self.data_by_id = {}1539self.dataid_counts = {}1540self.bad_chars = 015411542self.poll_sent = 01543self.sensor_id_poll_counts = {}15441545self.id_descriptions = {15460x5000: "status text (dynamic)",15470x5006: "Attitude and range (dynamic)",15480x800: "GPS lat or lon (600 with 1 sensor)",15490x5005: "Vel and Yaw",15500x5001: "AP status",15510x5002: "GPS Status",15520x5004: "Home",15530x5008: "Battery 2 status",15540x5003: "Battery 1 status",15550x5007: "parameters",15560x500A: "rpm",15570x500B: "terrain",15580x500C: "wind",15591560# SPort non-passthrough:15610x082F: "GALT", # gps altitude integer cm15620x040F: "TMP1", # Tmp115630x060F: "Fuel", # fuel % 0-10015640x041F: "TMP2", # Tmp215650x010F: "ALT", # baro alt cm15660x083F: "GSPD", # gps speed integer mm/s15670x084F: "HDG", # yaw in cd15680x020F: "CURR", # current dA15690x011F: "VSPD", # vertical speed cm/s15700x021F: "VFAS", # battery 1 voltage cV1571# 0x800: "GPS", ## comments as duplicated dictionary key15720x050E: "RPM1",157315740x34: "DOWNLINK1_ID",15750x67: "DOWNLINK2_ID",15760x0D: "UPLINK_ID",1577}15781579self.sensors_to_poll = [1580self.SENSOR_ID_VARIO,1581self.SENSOR_ID_FAS,1582self.SENSOR_ID_GPS,1583self.SENSOR_ID_RPM,1584self.SENSOR_ID_SP2UR,1585]1586self.next_sensor_id_to_poll = 0 # offset into sensors_to_poll15871588self.data_downlink_handler = None15891590self.last_poll_sensor = None1591self.last_data_time = None15921593def progress_tag(self):1594return "FRSkySPort"15951596def handle_data_downlink(self, some_bytes):1597self.progress("DOWNLINK %s" % (str(some_bytes),))1598if self.data_downlink_handler is not None:1599self.data_downlink_handler(some_bytes)1600self.last_data_time = self.get_time()16011602def handle_data(self, dataid, value):1603if dataid not in self.id_descriptions:1604raise KeyError("dataid 0x%02x" % dataid)1605self.progress("%s (0x%x)=%u" % (self.id_descriptions[dataid], dataid, value))1606self.data_by_id[dataid] = value1607if dataid not in self.dataid_counts:1608self.dataid_counts[dataid] = 01609self.dataid_counts[dataid] += 11610self.last_data_time = self.get_time()16111612def dump_dataid_counts_as_progress_messages(self):1613for dataid in self.dataid_counts:1614self.progress("0x%x: %u (%s)" % (dataid, self.dataid_counts[dataid], self.id_descriptions[dataid]))16151616def dump_sensor_id_poll_counts_as_progress_messages(self):1617for sensor_id in self.sensor_id_poll_counts:1618self.progress("(0x%x): %u" % (sensor_id, self.sensor_id_poll_counts[sensor_id]))16191620def read_bytestuffed_byte(self):1621b = self.buffer[0]1622if b == 0x7D:1623# byte-stuffed1624if len(self.buffer) < 2:1625self.consume = 01626return None1627self.consume = 21628b2 = self.buffer[1]1629if b2 == 0x5E:1630return self.START_STOP_SPORT1631if b2 == 0x5D:1632return self.BYTESTUFF_SPORT1633raise ValueError("Unknown stuffed byte (0x%02x)" % b2)1634return b16351636def calc_crc(self, byte):1637self.crc += byte1638self.crc += self.crc >> 81639self.crc &= 0xFF16401641def next_sensor(self):1642ret = self.sensors_to_poll[self.next_sensor_id_to_poll]1643self.next_sensor_id_to_poll += 11644if self.next_sensor_id_to_poll >= len(self.sensors_to_poll):1645self.next_sensor_id_to_poll = 01646return ret16471648def check_poll(self):1649now = self.get_time()1650# self.progress("check poll (%u)" % now)16511652# sometimes ArduPilot will not respond to a poll - for1653# example, if you poll an unhealthy RPM sensor then we will1654# *never* get a response back. So we must re-poll (which1655# moves onto the next sensor):1656if now - self.poll_sent > 5:1657if self.last_poll_sensor is None:1658self.progress("Re-polling (last poll sensor was None)")1659else:1660msg = ("Re-polling (last_poll_sensor=0x%02x state=%s)" %1661(self.last_poll_sensor, self.state))1662self.progress(msg)1663if self.state != self.state_WANT_FRAME_TYPE:1664raise ValueError("Expected to be wanting a frame type when repolling (state=%s)" % str(self.state))1665self.state = self.state_SEND_POLL16661667if self.state == self.state_SEND_POLL:1668sensor_id = self.next_sensor()1669self.progress("Sending poll for 0x%02x" % sensor_id)1670self.last_poll_sensor = sensor_id1671if sensor_id not in self.sensor_id_poll_counts:1672self.sensor_id_poll_counts[sensor_id] = 01673self.sensor_id_poll_counts[sensor_id] += 11674packet = SPortPollPacket(sensor_id)1675self.send_sport_packet(packet)1676self.state = self.state_WANT_FRAME_TYPE1677self.poll_sent = now16781679def send_sport_packets(self, packets):1680for packet in packets:1681self.send_sport_packet(packet)16821683def send_sport_packet(self, packet):1684stuffed = packet.for_wire()1685self.progress("Sending (%s) (%u)" %1686(["0x%02x" % x for x in bytearray(stuffed)], len(stuffed)))1687self.port.sendall(stuffed)16881689def send_mavlite_param_request_read(self, parameter_name):1690mavlite_msg = MAVliteMessage(1691mavutil.mavlink.MAVLINK_MSG_ID_PARAM_REQUEST_READ,1692bytearray(parameter_name.encode())1693)16941695packets = mavlite_msg.to_sport_packets()16961697self.send_sport_packets(packets)16981699def send_mavlite_param_set(self, parameter_name, value):1700out = bytearray(struct.pack("<f", value))1701out.extend(parameter_name.encode())17021703mavlite_msg = MAVliteMessage(1704mavutil.mavlink.MAVLINK_MSG_ID_PARAM_SET,1705out1706)17071708packets = mavlite_msg.to_sport_packets()17091710self.send_sport_packets(packets)17111712def send_mavlite_command_long(1713self,1714command,1715p1=None,1716p2=None,1717p3=None,1718p4=None,1719p5=None,1720p6=None,1721p7=None,1722):1723params = bytearray()1724seen_none = False1725for p in p1, p2, p3, p4, p5, p6, p7:1726if p is None:1727seen_none = True1728continue1729if seen_none:1730raise ValueError("Can't have values after Nones!")1731params.extend(bytearray(struct.pack("<f", p)))17321733out = bytearray(struct.pack("<H", command)) # first two bytes are command-id1734options = len(params) // 4 # low-three-bits is parameter count1735out.extend(bytearray(struct.pack("<B", options))) # second byte is options1736out.extend(params) # then the float values17371738mavlite_msg = MAVliteMessage(1739mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_LONG,1740out1741)17421743packets = mavlite_msg.to_sport_packets()17441745self.send_sport_packets(packets)17461747def update(self):1748if not self.connected:1749if not self.connect():1750self.progress("Failed to connect")1751return1752self.do_sport_read()1753self.check_poll()17541755def do_sport_read(self):1756self.buffer += self.do_read()1757self.consume = None1758while len(self.buffer):1759if self.consume is not None:1760self.buffer = self.buffer[self.consume:]1761if len(self.buffer) == 0:1762break1763self.consume = 11764b = self.buffer[0]1765# self.progress("Have (%s) bytes state=%s b=0x%02x" % (str(len(self.buffer)), str(self.state), b));1766if self.state == self.state_WANT_FRAME_TYPE:1767if b in [self.SPORT_DATA_FRAME, self.SPORT_DOWNLINK_FRAME]:1768self.frame = b1769self.crc = 01770self.calc_crc(b)1771self.state = self.state_WANT_ID11772continue1773# we may come into a stream mid-way, so we can't judge1774self.progress("############# Bad char %x" % b)1775raise ValueError("Bad char (0x%02x)" % b)1776self.bad_chars += 11777continue1778elif self.state == self.state_WANT_ID1:1779self.id1 = self.read_bytestuffed_byte()1780if self.id1 is None:1781break1782self.calc_crc(self.id1)1783self.state = self.state_WANT_ID21784continue1785elif self.state == self.state_WANT_ID2:1786self.id2 = self.read_bytestuffed_byte()1787if self.id2 is None:1788break1789self.calc_crc(self.id2)1790self.state = self.state_WANT_DATA1791self.data_bytes = []1792self.data = 01793continue1794elif self.state == self.state_WANT_DATA:1795data_byte = self.read_bytestuffed_byte()1796if data_byte is None:1797break1798self.calc_crc(data_byte)1799self.data = self.data | (data_byte << (8*(len(self.data_bytes))))1800self.data_bytes.append(data_byte)1801if len(self.data_bytes) == 4:1802self.state = self.state_WANT_CRC1803continue1804elif self.state == self.state_WANT_CRC:1805crc = self.read_bytestuffed_byte()1806if crc is None:1807break1808self.crc = 0xFF - self.crc1809dataid = (self.id2 << 8) | self.id11810if self.crc != crc:1811self.progress("Incorrect frsky checksum (received=%02x calculated=%02x id=0x%x)" % (crc, self.crc, dataid))1812# raise ValueError("Incorrect frsky checksum (want=%02x got=%02x id=0x%x)" % (crc, self.crc, dataid))1813else:1814if self.frame == self.SPORT_DOWNLINK_FRAME:1815self.handle_data_downlink([1816self.id1,1817self.id2,1818self.data_bytes[0],1819self.data_bytes[1],1820self.data_bytes[2],1821self.data_bytes[3]]1822)1823else:1824self.handle_data(dataid, self.data)1825self.state = self.state_SEND_POLL1826elif self.state == self.state_SEND_POLL:1827# this is done in check_poll1828self.progress("in send_poll state")1829pass1830else:1831raise ValueError("Unknown state (%s)" % self.state)18321833def get_data(self, dataid):1834try:1835return self.data_by_id[dataid]1836except KeyError:1837pass1838return None183918401841class FRSkyPassThrough(FRSkySPort):1842def __init__(self, destination_address, get_time=time.time):1843super(FRSkyPassThrough, self).__init__(destination_address,1844get_time=get_time)18451846self.sensors_to_poll = [self.SENSOR_ID_27]18471848def progress_tag(self):1849return "FRSkyPassthrough"185018511852class LocationInt(object):1853def __init__(self, lat, lon, alt, yaw):1854self.lat = lat1855self.lon = lon1856self.alt = alt1857self.yaw = yaw185818591860class Test(object):1861'''a test definition - information about a test'''1862def __init__(self, function, kwargs: dict | None = None, attempts=1, speedup=None):1863if kwargs is None:1864kwargs = {}1865self.name = function.__name__1866self.description = function.__doc__1867if self.description is None:1868raise ValueError("%s is missing a docstring" % self.name)1869self.function = function1870self.kwargs = kwargs1871self.attempts = attempts1872self.speedup = speedup187318741875class Result(object):1876'''a test result - pass, fail, exception, runtime, ....'''1877def __init__(self, test):1878self.test = test1879self.reason = None1880self.exception = None1881self.debug_filename = None1882self.time_elapsed = 0.01883# self.passed = False18841885def __str__(self):1886ret = " %s (%s)" % (self.test.name, self.test.description)1887if self.passed:1888return f"{ret} OK"1889if self.reason is not None:1890ret += f" ({self.reason} )"1891if self.exception is not None:1892ret += f" ({str(self.exception)})"1893if self.debug_filename is not None:1894ret += f" (see {self.debug_filename})"1895if self.time_elapsed is not None:1896ret += f" (duration {self.time_elapsed} s)"1897return ret189818991900class ValgrindFailedResult(Result):1901'''a custom Result to allow passing of Vaglrind failures around'''1902def __init__(self):1903super(ValgrindFailedResult, self).__init__(None)1904self.passed = False19051906def __str__(self):1907return "Valgrind error detected"190819091910class TestSuite(abc.ABC):1911"""Base abstract class.1912It implements the common function for all vehicle types.1913"""1914def __init__(self,1915binary,1916valgrind=False,1917callgrind=False,1918gdb=False,1919gdb_no_tui=False,1920speedup=None,1921frame=None,1922params=None,1923gdbserver=False,1924lldb=False,1925strace=False,1926breakpoints: list | None = None,1927disable_breakpoints=False,1928viewerip=None,1929use_map=False,1930_show_test_timings=False,1931logs_dir=None,1932force_ahrs_type=None,1933replay=False,1934sup_binaries: list | None = None,1935reset_after_every_test=False,1936force_32bit=False,1937ubsan=False,1938ubsan_abort=False,1939num_aux_imus=0,1940dronecan_tests=False,1941generate_junit=False,1942build_opts: dict | None = None,1943enable_fgview=False,1944move_logs_on_test_failure: bool = False,1945):1946if breakpoints is None:1947breakpoints = []1948if sup_binaries is None:1949sup_binaries = []1950if build_opts is None:1951build_opts = {}19521953self.start_time = time.time()19541955if binary is None:1956raise ValueError("Should always have a binary")19571958self.binary = binary1959self.valgrind = valgrind1960self.callgrind = callgrind1961self.gdb = gdb1962self.gdb_no_tui = gdb_no_tui1963self.lldb = lldb1964self.strace = strace1965self.frame = frame1966self.params = params1967self.gdbserver = gdbserver1968self.breakpoints = breakpoints1969self.disable_breakpoints = disable_breakpoints1970self.speedup = speedup1971if self.speedup is None:1972self.speedup = self.default_speedup()1973self.sup_binaries = sup_binaries1974self.reset_after_every_test = reset_after_every_test1975self.force_32bit = force_32bit1976self.ubsan = ubsan1977self.ubsan_abort = ubsan_abort1978self.build_opts = build_opts1979self.move_logs_on_test_failure = move_logs_on_test_failure1980self.num_aux_imus = num_aux_imus1981self.generate_junit = generate_junit1982if generate_junit:1983try:1984spec = importlib.util.find_spec("junitparser")1985if spec is None:1986raise ImportError1987except ImportError as e:1988raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python3 -m pip install junitparser")19891990self.mavproxy = None1991self._mavproxy = None # for auto-cleanup on failed tests1992self.mav = None1993self.viewerip = viewerip1994self.use_map = use_map1995self.contexts = []1996self.context_push()1997self.buildlog = None1998self.copy_tlog = False1999self.logfile = None2000self.max_set_rc_timeout = 02001self.last_wp_load = 02002self.forced_post_test_sitl_reboots = 02003self.run_tests_called = False2004self._show_test_timings = _show_test_timings2005self.test_timings = dict()2006self.total_waiting_to_arm_time = 02007self.waiting_to_arm_count = 02008self.force_ahrs_type = force_ahrs_type2009self.replay = replay2010if self.force_ahrs_type is not None:2011self.force_ahrs_type = int(self.force_ahrs_type)2012self.logs_dir = logs_dir2013self.timesync_number = 1372014self.last_progress_sent_as_statustext = None2015self.last_heartbeat_time_ms = None2016self.last_heartbeat_time_wc_s = 02017self.in_drain_mav = False2018self.tlog = None2019self.enable_fgview = enable_fgview20202021self.rc_thread = None2022self.rc_thread_should_quit = False2023self.rc_queue = Queue.Queue()20242025self.expect_list = []20262027self.start_mavproxy_count = 020282029self.last_sim_time_cached = 02030self.last_sim_time_cached_wallclock = 020312032# to autotest we do not want to go to the internet for tiles,2033# usually. Set this to False to gather tiles from internet in2034# the case there are new tiles required, then add them to the2035# repo and set this back to false:2036# the files will likely be downloaded to ~/.tilecache/SRTM32037self.terrain_in_offline_mode = True2038self.elevationmodel = mp_elevation.ElevationModel(2039cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"),2040offline=self.terrain_in_offline_mode2041)2042self.terrain_data_messages_sent = 0 # count of messages back2043self.dronecan_tests = dronecan_tests2044self.statustext_id = 12045self.message_hooks = [] # functions or MessageHook instances20462047def __del__(self):2048if self.rc_thread is not None:2049self.progress("Joining RC thread in __del__")2050self.rc_thread_should_quit = True2051self.rc_thread.join()2052self.rc_thread = None20532054def default_speedup(self):2055return 820562057def progress(self, text, send_statustext=True):2058"""Display autotest progress text."""2059delta_time = time.time() - self.start_time2060formatted_text = "AT-%06.1f: %s" % (delta_time, text)2061print(formatted_text)2062if (send_statustext and2063self.mav is not None and2064self.mav.port is not None and2065self.last_progress_sent_as_statustext != text):2066self.send_statustext(formatted_text)2067self.last_progress_sent_as_statustext = text20682069# following two functions swiped from autotest.py:2070@staticmethod2071def buildlogs_dirpath():2072return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))20732074def sitl_home(self):2075HOME = self.sitl_start_location()2076return "%f,%f,%u,%u" % (HOME.lat,2077HOME.lng,2078HOME.alt,2079HOME.heading)20802081def mavproxy_version(self):2082'''return the current version of mavproxy as a tuple e.g. (1,8,8)'''2083return util.MAVProxy_version()20842085def mavproxy_version_gt(self, major, minor, point):2086if os.getenv("AUTOTEST_FORCE_MAVPROXY_VERSION", None) is not None:2087return True2088(got_major, got_minor, got_point) = self.mavproxy_version()2089self.progress("Got: %s.%s.%s" % (got_major, got_minor, got_point))2090if got_major > major:2091return True2092elif got_major < major:2093return False2094if got_minor > minor:2095return True2096elif got_minor < minor:2097return False2098return got_point > point20992100def open_mavproxy_logfile(self):2101return MAVProxyLogFile()21022103def buildlogs_path(self, path):2104"""Return a string representing path in the buildlogs directory."""2105bits = [self.buildlogs_dirpath()]2106if isinstance(path, list):2107bits.extend(path)2108else:2109bits.append(path)2110return os.path.join(*bits)21112112def sitl_streamrate(self):2113"""Allow subclasses to override SITL streamrate."""2114return 1021152116def adjust_ardupilot_port(self, port):2117'''adjust port in case we do not wish to use the default range (5760 and 5501 etc)'''2118return port21192120def spare_network_port(self, offset=0):2121'''returns a network port which should be able to be bound'''2122if offset > 2:2123raise ValueError("offset too large")2124return 8000 + offset21252126def autotest_connection_string_to_ardupilot(self):2127return "tcp:127.0.0.1:%u" % self.adjust_ardupilot_port(5760)21282129def sitl_rcin_port(self, offset=0):2130if offset > 2:2131raise ValueError("offset too large")2132return 5501 + offset21332134def mavproxy_options(self):2135"""Returns options to be passed to MAVProxy."""2136ret = [2137'--streamrate=%u' % self.sitl_streamrate(),2138'--target-system=%u' % self.sysid_thismav(),2139'--target-component=1',2140]2141if self.viewerip:2142ret.append("--out=%s:14550" % self.viewerip)2143if self.use_map:2144ret.append('--map')21452146return ret21472148def vehicleinfo_key(self):2149return self.log_name()21502151def repeatedly_apply_parameter_filepath(self, filepath):2152if False:2153return self.repeatedly_apply_parameter_filepath_mavproxy(filepath)2154parameters = mavparm.MAVParmDict()2155# correct_parameters = set()2156if not parameters.load(filepath):2157raise ValueError("Param load failed")2158param_dict = {}2159for p in parameters.keys():2160param_dict[p] = parameters[p]2161self.set_parameters(param_dict)21622163def repeatedly_apply_parameter_filepath_mavproxy(self, filepath):2164'''keep applying a parameter file until no parameters changed'''2165for i in range(0, 3):2166self.mavproxy.send("param load %s\n" % filepath)2167while True:2168line = self.mavproxy.readline()2169match = re.match(".*Loaded [0-9]+ parameters.*changed ([0-9]+)",2170line)2171if match is not None:2172if int(match.group(1)) == 0:2173return2174break2175raise NotAchievedException()21762177def apply_defaultfile_parameters(self):2178"""Apply parameter file."""2179self.progress("Applying default parameters file")2180# setup test parameters2181if self.params is None:2182self.params = self.model_defaults_filepath(self.frame)2183for x in self.params:2184self.repeatedly_apply_parameter_filepath(x)21852186def count_lines_in_filepath(self, filepath):2187return len([i for i in open(filepath)])21882189def count_expected_fence_lines_in_filepath(self, filepath):2190count = 02191is_qgc = False2192for i in open(filepath):2193i = re.sub("#.*", "", i) # trim comments2194if i.isspace():2195# skip empty lines2196continue2197if re.match("QGC", i):2198# skip QGC header line2199is_qgc = True2200continue2201count += 12202if is_qgc:2203count += 2 # file doesn't include return point + closing point2204return count22052206def load_fence_using_mavproxy(self, mavproxy, filename):2207self.set_parameter("FENCE_TOTAL", 0)2208filepath = os.path.join(testdir, self.current_test_name_directory, filename)2209count = self.count_expected_fence_lines_in_filepath(filepath)2210mavproxy.send('fence load %s\n' % filepath)2211# self.mavproxy.expect("Loaded %u (geo-)?fence" % count)2212self.wait_parameter_value("FENCE_TOTAL", count, timeout=20)22132214def get_fence_point(self, idx, target_system=1, target_component=1):2215self.mav.mav.fence_fetch_point_send(target_system,2216target_component,2217idx)2218m = self.assert_receive_message("FENCE_POINT", timeout=2)2219self.progress("m: %s" % str(m))2220if m.idx != idx:2221raise NotAchievedException("Invalid idx returned (want=%u got=%u)" %2222(idx, m.seq))2223return m22242225def fencepoint_protocol_epsilon(self):2226return 0.0000222272228def roundtrip_fencepoint_protocol(self, offset, count, lat, lng, target_system=1, target_component=1):2229self.progress("Sending FENCE_POINT offs=%u count=%u" % (offset, count))2230self.mav.mav.fence_point_send(target_system,2231target_component,2232offset,2233count,2234lat,2235lng)22362237self.progress("Requesting fence point")2238m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)2239if abs(m.lat - lat) > self.fencepoint_protocol_epsilon():2240raise NotAchievedException("Did not get correct lat in fencepoint: got=%f want=%f" % (m.lat, lat))2241if abs(m.lng - lng) > self.fencepoint_protocol_epsilon():2242raise NotAchievedException("Did not get correct lng in fencepoint: got=%f want=%f" % (m.lng, lng))2243self.progress("Roundtrip OK")22442245def roundtrip_fence_using_fencepoint_protocol(self, loc_list, target_system=1, target_component=1, ordering=None):2246count = len(loc_list)2247offset = 02248self.set_parameter("FENCE_TOTAL", count)2249if ordering is None:2250ordering = range(count)2251elif len(ordering) != len(loc_list):2252raise ValueError("ordering list length mismatch")22532254for offset in ordering:2255loc = loc_list[offset]2256self.roundtrip_fencepoint_protocol(offset,2257count,2258loc.lat,2259loc.lng,2260target_system,2261target_component)22622263self.progress("Validating uploaded fence")2264returned_count = self.get_parameter("FENCE_TOTAL")2265if returned_count != count:2266raise NotAchievedException("Returned count mismatch (want=%u got=%u)" %2267(count, returned_count))2268for i in range(count):2269self.progress("Requesting fence point")2270m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)2271if abs(m.lat-loc.lat) > self.fencepoint_protocol_epsilon():2272raise NotAchievedException("Returned lat mismatch (want=%f got=%f" %2273(loc.lat, m.lat))2274if abs(m.lng-loc.lng) > self.fencepoint_protocol_epsilon():2275raise NotAchievedException("Returned lng mismatch (want=%f got=%f" %2276(loc.lng, m.lng))2277if m.count != count:2278raise NotAchievedException("Count mismatch (want=%u got=%u)" %2279(count, m.count))22802281def load_fence(self, filename):2282filepath = os.path.join(testdir, self.current_test_name_directory, filename)2283if not os.path.exists(filepath):2284filepath = self.generic_mission_filepath_for_filename(filename)2285self.progress("Loading fence from (%s)" % str(filepath))2286locs = []2287for line in open(filepath, 'rb'):2288if len(line) == 0:2289continue2290m = re.match(r"([-\d.]+)\s+([-\d.]+)\s*", line.decode('ascii'))2291if m is None:2292raise ValueError("Did not match (%s)" % line)2293locs.append(mavutil.location(float(m.group(1)), float(m.group(2)), 0, 0))2294if self.is_plane():2295# create return point as the centroid:2296total_lat = 02297total_lng = 02298total_cnt = 02299for loc in locs:2300total_lat += loc.lat2301total_lng += loc.lng2302total_cnt += 12303locs2 = [mavutil.location(total_lat/total_cnt,2304total_lng/total_cnt,23050,23060)] # return point2307locs2.extend(locs)2308locs2.append(copy.copy(locs2[1]))2309return self.roundtrip_fence_using_fencepoint_protocol(locs2)23102311self.upload_fences_from_locations([2312(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),2313])23142315def load_fence_using_mavwp(self, filename):2316filepath = os.path.join(testdir, self.current_test_name_directory, filename)2317if not os.path.exists(filepath):2318filepath = self.generic_mission_filepath_for_filename(filename)2319self.progress("Loading fence from (%s)" % str(filepath))2320items = self.mission_item_protocol_items_from_filepath(mavwp.MissionItemProtocol_Fence, filepath)2321self.check_fence_upload_download(items)23222323def send_reboot_command(self):2324self.mav.mav.command_long_send(self.sysid_thismav(),23251,2326mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,23271, # confirmation23281, # reboot autopilot23290,23300,23310,23320,23330,23340)23352336def reboot_check_valgrind_log(self):2337valgrind_log = util.valgrind_log_filepath(binary=self.binary,2338model=self.frame)2339if os.path.isfile(valgrind_log) and (os.path.getsize(valgrind_log) > 0):2340backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))2341shutil.move(valgrind_log, backup_valgrind_log)23422343def run_cmd_reboot(self):2344self.run_cmd_int(2345mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,2346p1=1, # reboot autopilot2347)23482349def run_cmd_enable_high_latency(self, new_state, run_cmd=None):2350if run_cmd is None:2351run_cmd = self.run_cmd2352p1 = 02353if new_state:2354p1 = 123552356run_cmd(2357mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY,2358p1=p1, # enable/disable2359)23602361def reboot_sitl_mav(self, required_bootcount=None, force=False):2362"""Reboot SITL instance using mavlink and wait for it to reconnect."""2363# we must make sure that stats have been reset - otherwise2364# when we reboot we'll reset statistics again and lose our2365# STAT_BOOTCNT increment:2366tstart = time.time()2367while True:2368if time.time() - tstart > 30:2369raise NotAchievedException("STAT_RESET did not go non-zero")2370if self.get_parameter('STAT_RESET', timeout_in_wallclock=True) != 0:2371break23722373old_bootcount = self.get_parameter('STAT_BOOTCNT')2374# ardupilot SITL may actually NAK the reboot; replace with2375# run_cmd when we don't do that.2376do_context = False2377if self.valgrind or self.callgrind:2378self.reboot_check_valgrind_log()2379self.progress("Stopping and restarting SITL")2380if getattr(self, 'valgrind_restart_customisations', None) is not None:2381self.customise_SITL_commandline(2382self.valgrind_restart_customisations,2383model=self.valgrind_restart_model,2384defaults_filepath=self.valgrind_restart_defaults_filepath,2385)2386else:2387self.stop_SITL()2388self.start_SITL(wipe=False)2389else:2390# receiving an ACK from the process turns out to be really2391# quite difficult. So just send it and hope for the best.2392self.progress("Sending reboot command")2393p6 = 02394if force:2395p6 = 20190226 # magic force-reboot value2396self.send_cmd(2397mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,2398p1=1,2399p2=1,2400p6=p6,2401)2402do_context = True2403if do_context:2404self.context_push()24052406def hook(mav, m):2407if m.get_type() != 'COMMAND_ACK':2408return2409if m.command != mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:2410return2411self.progress("While awaiting reboot received (%s)" % str(m))2412if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:2413raise NotAchievedException("Bad reboot ACK detected")2414self.install_message_hook_context(hook)24152416self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)24172418if do_context:2419self.context_pop()24202421def send_cmd_enter_cpu_lockup(self):2422"""Poke ArduPilot to stop the main loop from running"""2423self.mav.mav.command_long_send(self.sysid_thismav(),24241,2425mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,24261, # confirmation242742, # lockup autopilot242824, # no, really, we mean it242971, # seriously, we're not kidding243093, # we know exactly what we're24310,24320,24330)24342435def reboot_sitl(self,2436required_bootcount=None,2437force=False,2438check_position=True,2439mark_context=True,2440startup_location_dist_max=1,2441):2442"""Reboot SITL instance and wait for it to reconnect."""2443if self.armed() and not force:2444raise NotAchievedException("Reboot attempted while armed")2445self.progress("Rebooting SITL")2446self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force)2447self.do_heartbeats(force=True)2448if check_position and self.frame != 'sailboat': # sailboats drift with wind!2449self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max)2450if mark_context:2451self.context_get().reboot_sitl_was_done = True24522453def assert_armed(self):2454if not self.armed():2455raise NotAchievedException("Not armed")24562457def reboot_sitl_mavproxy(self, required_bootcount=None):2458"""Reboot SITL instance using MAVProxy and wait for it to reconnect."""2459old_bootcount = self.get_parameter('STAT_BOOTCNT')2460self.mavproxy.send("reboot\n")2461self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)24622463def detect_and_handle_reboot(self, old_bootcount, required_bootcount=None, timeout=10):2464tstart = time.time()2465if required_bootcount is None:2466required_bootcount = old_bootcount + 12467while True:2468if time.time() - tstart > timeout:2469raise AutoTestTimeoutException("Did not detect reboot")2470try:2471current_bootcount = self.get_parameter('STAT_BOOTCNT',2472timeout=1,2473attempts=1,2474verbose=True,2475timeout_in_wallclock=True)2476self.progress("current=%s required=%u" %2477(str(current_bootcount), required_bootcount))2478if current_bootcount == required_bootcount:2479break2480except NotAchievedException:2481pass2482except AutoTestTimeoutException:2483pass2484except ConnectionResetError:2485pass2486except socket.error:2487pass2488except Exception as e:2489self.progress("Got unexpected exception (%s)" % str(type(e)))2490pass24912492# empty mav to avoid getting old timestamps:2493self.do_timesync_roundtrip(timeout_in_wallclock=True)24942495self.progress("Calling initialise-after-reboot")2496self.initialise_after_reboot_sitl()24972498def scripting_restart(self):2499'''restart scripting subsystem'''2500self.progress("Restarting Scripting")2501self.run_cmd_int(2502mavutil.mavlink.MAV_CMD_SCRIPTING,2503p1=mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,2504timeout=5,2505)25062507def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):2508'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''2509self.do_timesync_roundtrip(timeout_in_wallclock=True)2510tstart = time.time()2511while True:2512if time.time() - tstart > timeout:2513raise NotAchievedException("Failed to set streamrate")2514self.mav.mav.request_data_stream_send(25151,25161,2517stream,2518streamrate,25191)2520m = self.mav.recv_match(type='SYSTEM_TIME',2521blocking=True,2522timeout=1)2523if m is not None:2524break25252526def set_streamrate_mavproxy(self, streamrate, timeout=10):2527tstart = time.time()2528while True:2529if time.time() - tstart > timeout:2530raise AutoTestTimeoutException("stream rate change failed")25312532self.mavproxy.send("set streamrate %u\n" % (streamrate))2533self.mavproxy.send("set streamrate\n")2534try:2535self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1)2536except pexpect.TIMEOUT:2537continue2538rate = self.mavproxy.match.group(1)2539# self.progress("rate: %s" % str(rate))2540if int(rate) == int(streamrate):2541break25422543if streamrate <= 0:2544return25452546self.progress("Waiting for SYSTEM_TIME for confirmation streams are working")2547self.drain_mav_unparsed()2548timeout = 602549tstart = time.time()2550while True:2551self.drain_all_pexpects()2552if time.time() - tstart > timeout:2553raise NotAchievedException("Did not get SYSTEM_TIME within %f seconds" % timeout)2554m = self.mav.recv_match(timeout=0.1)2555if m is None:2556continue2557# self.progress("Received (%s)" % str(m))2558if m.get_type() == 'SYSTEM_TIME':2559break2560self.drain_mav()25612562def htree_from_xml(self, xml_filepath):2563'''swiped from mavproxy_param.py'''2564xml = open(xml_filepath, 'rb').read()2565from lxml import objectify2566objectify.enable_recursive_str()2567tree = objectify.fromstring(xml)2568htree = {}2569for p in tree.vehicles.parameters.param:2570n = p.get('name').split(':')[1]2571htree[n] = p2572for lib in tree.libraries.parameters:2573for p in lib.param:2574n = p.get('name')2575htree[n] = p2576return htree25772578def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None):2579self.progress("Sending ABSD_VEHICLE message")2580new = here2581if offset_ne is not None:2582new = self.offset_location_ne(new, offset_ne[0], offset_ne[1])2583self.mav.mav.adsb_vehicle_send(258437, # ICAO address2585int(new.lat * 1e7),2586int(new.lng * 1e7),2587mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,2588int(here.alt*1000 + 10000), # 10m up25890, # heading in cdeg25900, # horizontal velocity cm/s25910, # vertical velocity cm/s2592"bob".encode("ascii"), # callsign2593mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,25941, # time since last communication259565535, # flags259617 # squawk2597)25982599def test_parameter_documentation_get_all_parameters(self):26002601xml_filepath = os.path.join(self.buildlogs_dirpath(), "apm.pdef.xml")2602param_parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'param_metadata', 'param_parse.py')2603try:2604os.unlink(xml_filepath)2605except OSError:2606pass2607vehicle = self.log_name()2608if vehicle == "HeliCopter":2609vehicle = "ArduCopter"2610if vehicle == "QuadPlane":2611vehicle = "ArduPlane"2612cmd = [param_parse_filepath, '--vehicle', vehicle]2613# cmd.append("--verbose")2614if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:2615self.progress("Failed param_parse.py (%s)" % vehicle)2616return False2617htree = self.htree_from_xml(xml_filepath)26182619target_system = self.sysid_thismav()2620target_component = 126212622self.customise_SITL_commandline([2623"--unhide-groups"2624])26252626(parameters, seq_id) = self.download_parameters(target_system, target_component)26272628self.reset_SITL_commandline()26292630fail = False2631for param in parameters.keys():2632if param not in htree:2633self.progress("%s not in XML" % param)2634fail = True2635if fail:2636raise NotAchievedException("Downloaded parameters missing in XML")26372638# FIXME: this should be doable if we filter out e.g BRD_* and CAN_*?2639# self.progress("Checking no extra parameters present in XML")2640# fail = False2641# for param in htree:2642# if param.startswith("SIM_"):2643# # too many of these to worry about2644# continue2645# if param not in parameters:2646# print("%s not in downloaded parameters but in XML" % param)2647# fail = True2648# if fail:2649# raise NotAchievedException("Extra parameters in XML")26502651def find_format_defines(self, lines):2652ret = {}2653for line in lines:2654if isinstance(line, bytes):2655line = line.decode("utf-8")2656m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)2657if m is None:2658continue2659(a, b) = (m.group(1), m.group(2))2660if a in ret:2661raise NotAchievedException("Duplicate define for (%s)" % a)2662ret[a] = b2663return ret26642665def vehicle_code_dirpath(self):2666'''returns path to vehicle-specific code directory e.g. ~/ardupilot/Rover'''2667dirname = self.log_name()2668if dirname == "QuadPlane":2669dirname = "ArduPlane"2670elif dirname == "HeliCopter":2671dirname = "ArduCopter"2672return os.path.join(self.rootdir(), dirname)26732674def find_LogStructureFiles(self):2675'''return list of files named LogStructure.h'''2676ret = []2677for root, _, files in os.walk(self.rootdir()):2678for f in files:2679if f == 'LogStructure.h':2680ret.append(os.path.join(root, f))2681if f == 'LogStructure_SBP.h':2682ret.append(os.path.join(root, f))2683return ret26842685def all_log_format_ids(self):2686'''parse C++ code to extract definitions of log messages'''2687structure_files = self.find_LogStructureFiles()2688structure_lines = []2689for f in structure_files:2690structure_lines.extend(open(f).readlines())26912692defines = self.find_format_defines(structure_lines)26932694ids = {}2695message_infos = []2696for f in structure_files:2697self.progress("structure file: %s" % f)2698state_outside = 02699state_inside = 12700state = state_outside27012702linestate_none = 452703linestate_within = 462704linestate = linestate_none2705debug = False2706if f == "/home/pbarker/rc/ardupilot/libraries/AP_HAL_ChibiOS/LogStructure.h":2707debug = True2708for line in open(f).readlines():2709if debug:2710print("line: %s" % line)2711if isinstance(line, bytes):2712line = line.decode("utf-8")2713line = re.sub("//.*", "", line) # trim comments2714if re.match(r"\s*$", line):2715# blank line2716continue2717if state == state_outside:2718if ("#define LOG_COMMON_STRUCTURES" in line or2719re.match("#define LOG_STRUCTURE_FROM_.*", line) or2720re.match("#define LOG_RTC_MESSAGE.*", line)):2721if debug:2722self.progress("Moving inside")2723state = state_inside2724continue2725if state == state_inside:2726if linestate == linestate_none:2727allowed_list = [2728'LOG_STRUCTURE_FROM_',2729'LOG_RTC_MESSAGE',2730]27312732allowed = False2733for a in allowed_list:2734if a in line:2735allowed = True2736if allowed:2737continue2738m = re.match(r"\s*{(.*)},\s*", line)2739if m is not None:2740# complete line2741if debug:2742print("Complete line: %s" % str(line))2743message_infos.append(m.group(1))2744continue2745m = re.match(r"\s*{(.*)\\", line)2746if m is None:2747if debug:2748self.progress("Moving outside")2749state = state_outside2750continue2751partial_line = m.group(1)2752if debug:2753self.progress("partial line")2754linestate = linestate_within2755continue2756if linestate == linestate_within:2757if debug:2758self.progress("Looking for close-brace")2759m = re.match("(.*)}", line)2760if m is None:2761if debug:2762self.progress("no close-brace")2763line = line.rstrip()2764newline = re.sub(r"\\$", "", line)2765if newline == line:2766raise NotAchievedException("Expected backslash at end of line")2767line = newline2768line = line.rstrip()2769# cpp-style string concatenation:2770if debug:2771self.progress("more partial line")2772line = re.sub(r'"\s*"', '', line)2773partial_line += line2774continue2775if debug:2776self.progress("found close-brace")2777message_infos.append(partial_line + m.group(1))2778linestate = linestate_none2779continue2780raise NotAchievedException("Bad line (%s)")27812782if linestate != linestate_none:2783raise NotAchievedException("Must be linestate-none at end of file")27842785# now look in the vehicle-specific logfile:2786filepath = os.path.join(self.vehicle_code_dirpath(), "Log.cpp")2787state_outside = 672788state_inside = 682789state = state_outside2790linestate_none = 892791linestate_within = 902792linestate = linestate_none2793for line in open(filepath, 'rb').readlines():2794if isinstance(line, bytes):2795line = line.decode("utf-8")2796line = re.sub("//.*", "", line) # trim comments2797if re.match(r"\s*$", line):2798# blank line2799continue2800if state == state_outside:2801if ("const LogStructure" in line or2802"const struct LogStructure" in line):2803state = state_inside2804continue2805if state == state_inside:2806if re.match("};", line):2807state = state_outside2808break2809if linestate == linestate_none:2810if "#if HAL_QUADPLANE_ENABLED" in line:2811continue2812if "#if FRAME_CONFIG == HELI_FRAME" in line:2813continue2814if "#if AC_PRECLAND_ENABLED" in line:2815continue2816if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line:2817continue2818if "#end" in line:2819continue2820if "LOG_COMMON_STRUCTURES" in line:2821continue2822m = re.match(r"\s*{(.*)},\s*", line)2823if m is not None:2824# complete line2825# print("Complete line: %s" % str(line))2826message_infos.append(m.group(1))2827continue2828m = re.match(r"\s*{(.*)", line)2829if m is None:2830raise NotAchievedException("Bad line %s" % line)2831partial_line = m.group(1)2832linestate = linestate_within2833continue2834if linestate == linestate_within:2835m = re.match("(.*)}", line)2836if m is None:2837line = line.rstrip()2838newline = re.sub(r"\\$", "", line)2839if newline == line:2840raise NotAchievedException("Expected backslash at end of line")2841line = newline2842line = line.rstrip()2843# cpp-style string concatenation:2844line = re.sub(r'"\s*"', '', line)2845partial_line += line2846continue2847message_infos.append(partial_line + m.group(1))2848linestate = linestate_none2849continue2850raise NotAchievedException("Bad line (%s)")28512852if state == state_inside:2853raise NotAchievedException("Should not be in state_inside at end")28542855for message_info in message_infos:2856print("message_info: %s" % str(message_info))2857for define in defines:2858message_info = re.sub(define, defines[define], message_info)2859m = re.match(r'\s*LOG_\w+\s*,\s*(?:sizeof|RLOG_SIZE)\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*(true|false))?\s*$', message_info) # noqa2860if m is None:2861print("NO MATCH")2862continue2863(name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5))2864if name in ids:2865raise NotAchievedException("Already seen a (%s) message" % name)2866ids[name] = {2867"name": name,2868"format": fmt,2869"labels": labels,2870"units": units,2871"multipliers": multipliers,2872}28732874# now look for Log_Write(...) messages:2875base_directories = [2876os.path.join(self.rootdir(), 'libraries'),2877self.vehicle_code_dirpath(),2878]2879log_write_statements = []2880for base_directory in base_directories:2881for root, dirs, files in os.walk(base_directory):2882state_outside = 372883state_inside = 382884state = state_outside2885for f in files:2886if not re.search("[.]cpp$", f):2887continue2888filepath = os.path.join(root, f)2889if "AP_Logger/examples" in filepath:2890# this is the sample file which contains examples...2891continue2892count = 02893for line in open(filepath, 'rb').readlines():2894if isinstance(line, bytes):2895line = line.decode("utf-8")2896if state == state_outside:2897if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or2898re.match(r"\s*logger[.]Write(?:Streaming)?\(", line)):2899state = state_inside2900line = re.sub("//.*", "", line) # trim comments2901log_write_statement = line2902continue2903if state == state_inside:2904line = re.sub("//.*", "", line) # trim comments2905# cpp-style string concatenation:2906line = re.sub(r'"\s*"', '', line)2907log_write_statement += line2908if re.match(r".*\);", line):2909log_write_statements.append(log_write_statement)2910state = state_outside2911count += 12912if state != state_outside:2913raise NotAchievedException("Expected to be outside at end of file")2914# print("%s has %u lines" % (f, count))2915# change all whitespace to single space2916log_write_statements = [re.sub(r"\s+", " ", x) for x in log_write_statements]2917# print("Got log-write-statements: %s" % str(log_write_statements))2918results = []2919for log_write_statement in log_write_statements:2920for define in defines:2921log_write_statement = re.sub(define, defines[define], log_write_statement)2922# fair warning: order is important here because of the2923# NKT/XKT special case below....2924my_re = r' logger[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'2925m = re.match(my_re, log_write_statement)2926if m is None:2927my_re = r' AP::logger\(\)[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'2928m = re.match(my_re, log_write_statement)2929if m is None:2930raise NotAchievedException("Did not match (%s) with (%s)" % (log_write_statement, str(my_re)))2931else:2932results.append((m.group(1), m.group(2)))29332934for result in results:2935(name, labels) = result2936if name in ids:2937raise Exception("Already have id for (%s)" % name)2938# self.progress("Adding Log_Write result (%s)" % name)2939ids[name] = {2940"name": name,2941"labels": labels,2942}29432944if len(ids) == 0:2945raise NotAchievedException("Did not get any ids")29462947return ids29482949def LoggerDocumentation_whitelist(self):2950'''returns a set of messages which we do not want to see2951documentation for'''29522953ret = set()29542955# messages not expected to be on particular vehicles. Nothing2956# needs fixing below this point, unless you can come up with a2957# better way to avoid this list!29582959# We extract all message that need to be documented from the2960# code, but we don't pay attention to which vehicles will use2961# those messages. We *do* care about the documented messages2962# for a vehicle as we follow the tree created by the2963# documentation (eg. @Path:2964# ../libraries/AP_LandingGear/AP_LandingGear.cpp). The lists2965# here have been created to fix this discrepancy.2966vinfo_key = self.vehicleinfo_key()2967if vinfo_key != 'ArduPlane' and vinfo_key != 'ArduCopter' and vinfo_key != 'Helicopter':2968ret.update([2969"ATUN", # Plane and Copter have ATUN messages2970])2971if vinfo_key != 'ArduPlane':2972ret.update([2973"TECS", # only Plane has TECS2974"TEC2", # only Plane has TECS2975"TEC3", # only Plane has TECS2976"TEC4", # only Plane has TECS2977"SOAR", # only Planes can truly soar2978"SORC", # soaring is pure magic2979"QBRK", # quadplane2980"FWDT", # quadplane2981"VAR", # variometer only applicable on Plane2982])2983if vinfo_key != 'ArduCopter' and vinfo_key != "Helicopter":2984ret.update([2985"ARHS", # autorotation2986"AROT", # autorotation2987"ARSC", # autorotation2988"ATDH", # heli autotune2989"ATNH", # heli autotune2990"ATSH", # heli autotune2991"GMB1", # sologimbal2992"GMB2", # sologimbal2993"SURF", # surface-tracking2994])2995# end not-expected-to-be-fixed block29962997return ret29982999def LoggerDocumentation(self):3000'''Test Onboard Logging Generation'''3001xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml")3002parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py')3003try:3004os.unlink(xml_filepath)3005except OSError:3006pass3007vehicle = self.log_name()3008if vehicle == 'BalanceBot':3009# same binary and parameters as Rover3010return3011vehicle_map = {3012"ArduCopter": "Copter",3013"HeliCopter": "Copter",3014"ArduPlane": "Plane",3015"QuadPlane": "Plane",3016"Rover": "Rover",3017"AntennaTracker": "Tracker",3018"ArduSub": "Sub",3019}3020vehicle = vehicle_map[vehicle]30213022cmd = [parse_filepath, '--vehicle', vehicle]3023# cmd.append("--verbose")3024if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:3025self.progress("Failed parse.py (%s)" % vehicle)3026return False3027length = os.path.getsize(xml_filepath)3028min_length = 10243029if length < min_length:3030raise NotAchievedException("short xml file (%u < %u)" %3031(length, min_length))3032self.progress("xml file length is %u" % length)30333034from lxml import objectify3035xml = open(xml_filepath, 'rb').read()3036objectify.enable_recursive_str()3037tree = objectify.fromstring(xml)30383039whitelist = self.LoggerDocumentation_whitelist()30403041docco_ids = {}3042for thing in tree.logformat:3043name = str(thing.get("name"))3044docco_ids[name] = {3045"name": name,3046"labels": [],3047}3048if getattr(thing.fields, 'field', None) is None:3049if name in whitelist:3050continue3051raise NotAchievedException("no doc fields for %s" % name)3052for field in thing.fields.field:3053# print("field: (%s)" % str(field))3054fieldname = field.get("name")3055# print("Got (%s.%s)" % (name,str(fieldname)))3056docco_ids[name]["labels"].append(fieldname)30573058code_ids = self.all_log_format_ids()3059# self.progress("Code ids: (%s)" % str(sorted(code_ids.keys())))3060# self.progress("Docco ids: (%s)" % str(sorted(docco_ids.keys())))30613062undocumented = set()3063overdocumented = set()3064for name in sorted(code_ids.keys()):3065if name not in docco_ids:3066if name not in whitelist:3067undocumented.add(name)3068continue3069if name in whitelist:3070overdocumented.add(name)3071seen_labels = {}3072for label in code_ids[name]["labels"].split(","):3073if label in seen_labels:3074raise NotAchievedException("%s.%s is duplicate label" %3075(name, label))3076seen_labels[label] = True3077if label not in docco_ids[name]["labels"]:3078msg = ("%s.%s not in documented fields (have (%s))" %3079(name, label, ",".join(docco_ids[name]["labels"])))3080if name in whitelist:3081self.progress(msg)3082# a lot of our Replay messages have names but3083# nothing more3084try:3085overdocumented.remove(name)3086except KeyError:3087pass3088continue3089raise NotAchievedException(msg)30903091if len(undocumented):3092for name in sorted(undocumented):3093self.progress(f"Undocumented message: {name}")3094raise NotAchievedException("Undocumented messages found")3095if len(overdocumented):3096for name in sorted(overdocumented):3097self.progress(f"Message documented when it shouldn't be: {name}")3098raise NotAchievedException("Overdocumented messages found")30993100missing = []3101for name in sorted(docco_ids):3102if name not in code_ids and name not in whitelist:3103missing.append(name)3104continue3105for label in docco_ids[name]["labels"]:3106if label not in code_ids[name]["labels"].split(","):3107# "name" was found in the XML, so was found in an3108# @LoggerMessage markup line, but was *NOT* found3109# in our bodgy parsing of the C++ code (in a3110# Log_Write call or in the static structures)3111raise NotAchievedException("documented field %s.%s not found in code" %3112(name, label))3113if len(missing) > 0:3114raise NotAchievedException("Documented messages (%s) not in code" % missing)31153116def initialise_after_reboot_sitl(self):31173118# after reboot stream-rates may be zero. Request streams.3119self.drain_mav()3120self.wait_heartbeat()3121self.set_streamrate(self.sitl_streamrate())3122self.progress("Reboot complete")31233124def customise_SITL_commandline(self,3125customisations,3126model=None,3127defaults_filepath=None,3128wipe=False,3129set_streamrate_callback=None,3130binary=None):3131'''customisations could be "--serial5=sim:nmea" '''3132self.contexts[-1].sitl_commandline_customised = True3133self.mav.close()3134self.stop_SITL()3135self.start_SITL(binary=binary,3136model=model,3137defaults_filepath=defaults_filepath,3138customisations=customisations,3139wipe=wipe)3140self.mav.do_connect()3141tstart = time.time()3142while True:3143if time.time() - tstart > 30:3144raise NotAchievedException("Failed to customise")3145try:3146m = self.wait_heartbeat(drain_mav=True)3147if m.type == 0:3148self.progress("Bad heartbeat: %s" % str(m))3149continue3150except IOError:3151pass3152break3153if set_streamrate_callback is not None:3154set_streamrate_callback()3155else:3156self.set_streamrate(self.sitl_streamrate())31573158self.assert_receive_message('RC_CHANNELS', timeout=15)31593160# stash our arguments in case we need to preserve them in3161# reboot_sitl with Valgrind active:3162if self.valgrind or self.callgrind:3163self.valgrind_restart_model = model3164self.valgrind_restart_defaults_filepath = defaults_filepath3165self.valgrind_restart_customisations = customisations31663167def default_parameter_list(self):3168ret = {3169'LOG_DISARMED': 1,3170# also lower logging rate to reduce log sizes3171'LOG_DARM_RATEMAX': 5,3172'LOG_FILE_RATEMAX': 10,3173}3174if self.force_ahrs_type is not None:3175if self.force_ahrs_type == 2:3176ret["EK2_ENABLE"] = 13177if self.force_ahrs_type == 3:3178ret["EK3_ENABLE"] = 13179ret["AHRS_EKF_TYPE"] = self.force_ahrs_type3180if self.num_aux_imus > 0:3181ret["SIM_IMU_COUNT"] = self.num_aux_imus + 33182if self.replay:3183ret["LOG_REPLAY"] = 13184return ret31853186def apply_default_parameter_list(self):3187self.set_parameters(self.default_parameter_list())31883189def apply_default_parameters(self):3190self.apply_defaultfile_parameters()3191self.apply_default_parameter_list()3192self.reboot_sitl()31933194def reset_SITL_commandline(self):3195self.progress("Resetting SITL commandline to default")3196self.stop_SITL()3197try:3198del self.valgrind_restart_customisations3199except Exception:3200pass3201self.start_SITL(wipe=True)3202self.set_streamrate(self.sitl_streamrate())3203self.apply_default_parameters()3204self.progress("Reset SITL commandline to default")32053206def pause_SITL(self):3207'''temporarily stop the SITL process from running. Note that3208simulation time will not move forward!'''3209# self.progress("Pausing SITL")3210if sys.platform == 'cygwin':3211# Maintain original behaviour under cygwin as SIGTSTP has not been tested3212self.sitl.kill(signal.SIGSTOP)32133214else:3215# SIGTSTP can be ignored by GDB allowing easier debugging rather than having GDB break at every pause3216# EG add:3217# handle SIGTSTP nostop noprint pass3218# handle SIGCONT nostop noprint pass3219self.sitl.kill(signal.SIGTSTP)32203221def unpause_SITL(self):3222# self.progress("Unpausing SITL")3223self.sitl.kill(signal.SIGCONT)32243225def stop_SITL(self):3226self.progress("Stopping SITL")3227self.expect_list_remove(self.sitl)3228util.pexpect_close(self.sitl)3229self.sitl = None32303231def start_test(self, description):3232self.progress("##################################################################################")3233self.progress("########## %s ##########" % description)3234self.progress("##################################################################################")32353236def try_symlink_tlog(self):3237self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")3238self.progress("buildlog=%s" % self.buildlog)3239if os.path.exists(self.buildlog):3240os.unlink(self.buildlog)3241try:3242os.link(self.logfile, self.buildlog)3243except OSError as error:3244self.progress("OSError [%d]: %s" % (error.errno, error.strerror))3245self.progress("Problem: Failed to create link: %s => %s, "3246"will copy tlog manually to target location" %3247(self.logfile, self.buildlog))3248self.copy_tlog = True32493250#################################################3251# GENERAL UTILITIES3252#################################################3253def expect_list_clear(self):3254"""clear the expect list."""3255for p in self.expect_list[:]:3256self.expect_list.remove(p)32573258def expect_list_extend(self, list_to_add):3259"""Extend the expect list."""3260self.expect_list.extend(list_to_add)32613262def expect_list_add(self, item):3263"""Extend the expect list."""3264self.expect_list.extend([item])32653266def expect_list_remove(self, item):3267"""Remove item from the expect list."""3268self.expect_list.remove(item)32693270def heartbeat_interval_ms(self):3271c = self.context_get()3272if c is None:3273return 10003274return c.heartbeat_interval_ms32753276def set_heartbeat_interval_ms(self, interval_ms):3277c = self.context_get()3278if c is None:3279raise ValueError("No context")3280if c.original_heartbeat_interval_ms is None:3281c.original_heartbeat_interval_ms = c.heartbeat_interval_ms3282c.heartbeat_interval_ms = interval_ms32833284def set_heartbeat_rate(self, rate_hz):3285if rate_hz == 0:3286self.set_heartbeat_interval_ms(None)3287return3288self.set_heartbeat_interval_ms(1000.0/rate_hz)32893290def do_heartbeats(self, force=False):3291# self.progress("do_heartbeats")3292if self.heartbeat_interval_ms() is None and not force:3293return3294x = self.mav.messages.get("SYSTEM_TIME", None)3295now_wc = time.time()3296if (force or3297x is None or3298self.last_heartbeat_time_ms is None or3299self.last_heartbeat_time_ms < x.time_boot_ms or3300x.time_boot_ms - self.last_heartbeat_time_ms > self.heartbeat_interval_ms() or3301now_wc - self.last_heartbeat_time_wc_s > 1):3302if x is not None:3303self.last_heartbeat_time_ms = x.time_boot_ms3304self.last_heartbeat_time_wc_s = now_wc3305self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,3306mavutil.mavlink.MAV_AUTOPILOT_INVALID,33070,33080,33090)33103311def drain_all_pexpects(self):3312for p in self.expect_list:3313util.pexpect_drain(p)33143315def idle_hook(self, mav):3316"""Called when waiting for a mavlink message."""3317if self.in_drain_mav:3318return3319self.drain_all_pexpects()33203321class MessageHook():3322'''base class for objects that watch the message stream and check for3323validity of fields'''3324def __init__(self, suite):3325self.suite = suite33263327def process(self):3328pass33293330def progress_prefix(self):3331return ""33323333def progress(self, string):3334string = self.progress_prefix() + string3335self.suite.progress(string)33363337def hook_removed(self):3338pass33393340class FailFastStatusText(MessageHook):3341'''watches STATUSTEXT message; any message matching passed-in3342patterns causes a NotAchievedException to be thrown'''3343def __init__(self, suite, texts, regex: bool = False):3344super(TestSuite.FailFastStatusText, self).__init__(suite)3345if isinstance(texts, str):3346texts = [texts]3347self.texts = texts3348self.regex = regex33493350def progress_prefix(self):3351return "FFST: "33523353def process(self, mav, m):3354if m.get_type() != 'STATUSTEXT':3355return33563357for text in self.texts:3358if self.regex:3359found = re.match(text, m.text)3360else:3361found = text.lower() in m.text.lower()3362if found:3363raise NotAchievedException(f"Fail-fast text found: {m.text}")33643365class ValidateIntPositionAgainstSimState(MessageHook):3366'''monitors a message containing a position containing lat/lng in 1e7,3367makes sure it stays close to SIMSTATE'''3368def __init__(self, suite, other_int_message_name, max_allowed_divergence=150):3369super(TestSuite.ValidateIntPositionAgainstSimState, self).__init__(suite)3370self.other_int_message_name = other_int_message_name3371self.max_allowed_divergence = max_allowed_divergence3372self.max_divergence = 03373self.gpi = None3374self.simstate = None3375self.last_print = 03376self.min_print_interval = 1 # seconds33773378def progress_prefix(self):3379return "VIPASS: "33803381def process(self, mav, m):3382if m.get_type() == self.other_int_message_name:3383self.gpi = m3384elif m.get_type() == 'SIMSTATE':3385self.simstate = m3386if self.gpi is None:3387return3388if self.simstate is None:3389return33903391divergence = self.suite.get_distance_int(self.gpi, self.simstate)3392if (time.time() - self.last_print > self.min_print_interval or3393divergence > self.max_divergence):3394self.progress(f"distance(SIMSTATE,{self.other_int_message_name})={divergence:.5f}m")3395self.last_print = time.time()3396if divergence > self.max_divergence:3397self.max_divergence = divergence3398if divergence > self.max_allowed_divergence:3399raise NotAchievedException(3400"%s diverged from simstate by %fm (max=%fm" %3401(self.other_int_message_name, divergence, self.max_allowed_divergence,))34023403def hook_removed(self):3404self.progress(f"Maximum divergence was {self.max_divergence}m (max={self.max_allowed_divergence}m)")34053406class ValidateGlobalPositionIntAgainstSimState(ValidateIntPositionAgainstSimState):3407def __init__(self, suite, **kwargs):3408super(TestSuite.ValidateGlobalPositionIntAgainstSimState, self).__init__(suite, 'GLOBAL_POSITION_INT', **kwargs)34093410class ValidateAHRS3AgainstSimState(ValidateIntPositionAgainstSimState):3411def __init__(self, suite, **kwargs):3412super(TestSuite.ValidateAHRS3AgainstSimState, self).__init__(suite, 'AHRS3', **kwargs)34133414def message_hook(self, mav, msg):3415"""Called as each mavlink msg is received."""3416# print("msg: %s" % str(msg))3417if msg.get_type() == 'STATUSTEXT':3418self.progress("AP: %s" % msg.text, send_statustext=False)34193420self.write_msg_to_tlog(msg)34213422self.idle_hook(mav)3423self.do_heartbeats()34243425for h in self.message_hooks:3426if isinstance(h, TestSuite.MessageHook):3427h.process(mav, msg)3428continue3429# assume it's a function3430h(mav, msg)34313432def send_message_hook(self, msg, x):3433self.write_msg_to_tlog(msg)34343435def write_msg_to_tlog(self, msg):3436usec = int(time.time() * 1.0e6)3437if self.tlog is None:3438tlog_filename = "autotest-%u.tlog" % usec3439self.tlog = open(tlog_filename, 'wb')34403441content = bytearray(struct.pack('>Q', usec) + msg.get_msgbuf())3442self.tlog.write(content)34433444def expect_callback(self, e):3445"""Called when waiting for a expect pattern."""3446for p in self.expect_list:3447if p == e:3448continue3449util.pexpect_drain(p)3450self.drain_mav(quiet=True)3451self.do_heartbeats()34523453def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False):3454'''drain all data on mavlink connection mav (defaulting to self.mav).3455It is assumed that this connection is connected to the normal3456simulation.'''3457if mav is None:3458mav = self.mav3459count = 03460tstart = time.time()3461self.pause_SITL()3462# sometimes we recv() when the process is likely to go away..3463old_autoreconnect = mav.autoreconnect3464mav.autoreconnect = False3465while True:3466try:3467this = mav.recv(1000000)3468except Exception:3469mav.autoreconnect = old_autoreconnect3470self.unpause_SITL()3471raise3472if len(this) == 0:3473break3474count += len(this)3475mav.autoreconnect = old_autoreconnect3476self.unpause_SITL()3477if quiet:3478return3479tdelta = time.time() - tstart3480if tdelta == 0:3481rate = "instantly"3482else:3483rate = "%f/s" % (count/float(tdelta),)3484self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate), send_statustext=False)3485if freshen_sim_time:3486self.get_sim_time()34873488def drain_mav(self, mav=None, unparsed=False, quiet=True):3489'''parse all data available on connection mav (defaulting to3490self.mav). It is assumed that mav is connected to the normal3491simulation'''3492if unparsed:3493return self.drain_mav_unparsed(quiet=quiet, mav=mav)3494if mav is None:3495mav = self.mav3496self.in_drain_mav = True3497count = 03498tstart = time.time()3499timeout = 1203500failed_to_drain = False3501self.pause_SITL()3502# sometimes we recv() when the process is likely to go away..3503old_autoreconnect = mav.autoreconnect3504mav.autoreconnect = False3505while True:3506try:3507receive_result = mav.recv_msg()3508except Exception:3509mav.autoreconnect = True3510self.unpause_SITL()3511raise3512if receive_result is None:3513break3514count += 13515if time.time() - tstart > timeout:3516# ArduPilot can produce messages faster than we can3517# consume them. Until a better solution is found,3518# just die if that seems to be the case:3519failed_to_drain = True3520quiet = False3521mav.autoreconnect = old_autoreconnect3522self.unpause_SITL()3523if quiet:3524self.in_drain_mav = False3525return3526tdelta = time.time() - tstart3527if tdelta == 0:3528rate = "instantly"3529else:3530rate = "%f/s" % (count/float(tdelta),)35313532if not quiet:3533self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False)35343535if failed_to_drain:3536raise NotAchievedException("Did not fully drain MAV within %ss" % timeout)35373538self.in_drain_mav = False35393540def do_timesync_roundtrip(self, quiet=False, timeout_in_wallclock=False):3541if not quiet:3542self.progress("Doing timesync roundtrip")3543if timeout_in_wallclock:3544tstart = time.time()3545else:3546tstart = self.get_sim_time()3547self.mav.mav.timesync_send(0, self.timesync_number * 1000 + self.mav.source_system)3548while True:3549if timeout_in_wallclock:3550now = time.time()3551else:3552now = self.get_sim_time_cached()3553if now - tstart > 5:3554raise AutoTestTimeoutException("Did not get timesync response")3555m = self.mav.recv_match(type='TIMESYNC', blocking=True, timeout=1)3556if not quiet:3557self.progress("Received: %s" % str(m))3558if m is None:3559continue3560if m.ts1 % 1000 != self.mav.source_system:3561self.progress("this isn't a response to our timesync (%s)" % (m.ts1 % 1000))3562continue3563if m.tc1 == 0:3564# this should also not happen:3565self.progress("this is a timesync request, which we don't answer")3566continue3567if int(m.ts1 / 1000) != self.timesync_number:3568self.progress("this isn't the one we just sent")3569continue3570if m.get_srcSystem() != self.mav.target_system:3571self.progress("response from system other than our target (want=%u got=%u" %3572(self.mav.target_system, m.get_srcSystem()))3573continue3574# no component check ATM because we send broadcast...3575# if m.get_srcComponent() != self.mav.target_component:3576# self.progress("response from component other than our target (got=%u want=%u)" % (m.get_srcComponent(), self.mav.target_component)) # noqa3577# continue3578if not quiet:3579self.progress("Received TIMESYNC response after %fs" % (now - tstart))3580self.timesync_number += 13581break35823583def log_filepath(self, lognum):3584'''return filepath to lognum (where lognum comes from LOG_ENTRY'''3585log_list = self.log_list()3586return log_list[lognum-1]35873588def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):3589tocheck = len(bytes1)3590if maxlen is not None:3591if tocheck > maxlen:3592tocheck = maxlen3593for i in range(0, tocheck):3594if bytes1[i] != bytes2[i]:3595raise NotAchievedException("differ at offset %u" % i)35963597def assert_home_position_not_set(self):3598try:3599self.poll_home_position()3600except NotAchievedException:3601return36023603# if home.lng != 0: etc36043605raise NotAchievedException("Home is set when it shouldn't be")36063607def HIGH_LATENCY2(self):3608'''test sending of HIGH_LATENCY2'''36093610# set airspeed sensor type to DLVR for air temperature message testing3611if not self.is_plane():3612# Plane does not have enable parameter3613self.set_parameter("ARSPD_ENABLE", 1)3614self.set_parameter("ARSPD_BUS", 2)3615self.set_parameter("ARSPD_TYPE", 7)3616self.reboot_sitl()36173618self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True, verbose=True, timeout=30)36193620# should not be getting HIGH_LATENCY2 by default3621m = self.assert_not_receive_message('HIGH_LATENCY2', timeout=2)3622m = self.poll_message("HIGH_LATENCY2")3623if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:3624raise NotAchievedException("Expected GPS to be OK")3625self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)3626self.set_parameter("SIM_GPS1_TYPE", 0)3627self.delay_sim_time(10)3628self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)3629m = self.poll_message("HIGH_LATENCY2")3630self.progress(self.dump_message_verbose(m))3631if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) == 0:3632raise NotAchievedException("Expected GPS to be failed")36333634self.start_subtest("HIGH_LATENCY2 location")3635self.set_parameter("SIM_GPS1_TYPE", 1)3636self.delay_sim_time(10)3637m = self.poll_message("HIGH_LATENCY2")3638self.progress(self.dump_message_verbose(m))3639loc = mavutil.location(m.latitude, m.longitude, m.altitude, 0)3640dist = self.get_distance_int(loc, self.sim_location_int())36413642if dist > 1:3643raise NotAchievedException("Bad location from HIGH_LATENCY2")36443645self.start_subtest("HIGH_LATENCY2 Air Temperature")3646m = self.poll_message("HIGH_LATENCY2")3647mavutil.dump_message_verbose(sys.stdout, m)36483649if m.temperature_air == -128: # High_Latency2 defaults to INT8_MIN for no temperature available3650raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2")3651self.HIGH_LATENCY2_links()36523653def context_set_send_debug_trap_on_exceptions(self, value=True):3654'''send a debug trap to ArduPilot if an ErrorException is raised.'''36553656# this is a diagnostic tool, only expected to be used for3657# debugging, never for committed code36583659def trace_calls(frame, event, arg):3660if event == 'exception':3661exc_type, exc_value, tb = arg3662if issubclass(exc_type, ErrorException):3663print(f"[Tracer] Exception raised: {exc_type}")3664self.send_debug_trap()3665return trace_calls36663667context = self.context_get()36683669if value:3670if sys.gettrace() is not None:3671raise ValueError("Can't trace, something else already is")3672sys.settrace(trace_calls)3673context.raising_debug_trap_on_exceptions = True3674return36753676if not sys.gettrace():3677raise ValueError("Expected to see something tracing")36783679context.raising_debug_trap_on_exceptions = False3680sys.settrace(None)36813682def context_set_message_rate_hz(self, id, rate_hz, run_cmd=None):3683if run_cmd is None:3684run_cmd = self.run_cmd36853686overridden_message_rates = self.context_get().overridden_message_rates36873688if id not in overridden_message_rates:3689overridden_message_rates[id] = self.measure_message_rate(id)36903691self.set_message_rate_hz(id, rate_hz, run_cmd=run_cmd)36923693def HIGH_LATENCY2_links(self):36943695self.start_subtest("SerialProtocol_MAVLinkHL links")36963697ex = None3698self.context_push()3699mav2 = None3700try:37013702self.set_parameter("SERIAL2_PROTOCOL", 43) # HL)37033704self.reboot_sitl()37053706mav2 = mavutil.mavlink_connection(3707"tcp:localhost:%u" % self.adjust_ardupilot_port(5763),3708robust_parsing=True,3709source_system=7,3710source_component=7,3711)37123713self.start_subsubtest("Don't get HIGH_LATENCY2 by default")3714for mav in self.mav, mav2:3715self.assert_not_receive_message('HIGH_LATENCY2', mav=mav, timeout=10)37163717self.start_subsubtest("Get HIGH_LATENCY2 upon link enabled only on HL link")3718for run_cmd in self.run_cmd, self.run_cmd_int:3719self.run_cmd_enable_high_latency(True, run_cmd=run_cmd)3720self.assert_receive_message("HIGH_LATENCY2", mav=mav2, timeout=10)3721self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)37223723self.start_subsubtest("Not get HIGH_LATENCY2 upon HL disable")3724self.run_cmd_enable_high_latency(False, run_cmd=run_cmd)3725self.delay_sim_time(10)3726self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)3727self.drain_mav(mav2)3728self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)37293730self.start_subsubtest("Stream rate adjustments")3731self.run_cmd_enable_high_latency(True)3732self.assert_message_rate_hz("HIGH_LATENCY2", 0.2, ndigits=1, mav=mav2, sample_period=60)3733for test_rate in (1, 0.1, 2):3734self.test_rate(3735"HIGH_LATENCY2 on enabled link",3736test_rate,3737test_rate,3738mav=mav2,3739ndigits=1,3740victim_message="HIGH_LATENCY2",3741message_rate_sample_period=60,3742)3743self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)3744self.run_cmd_enable_high_latency(False)37453746self.start_subsubtest("Not get HIGH_LATENCY2 after disabling after playing with rates")3747self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)3748self.delay_sim_time(1)3749self.drain_mav(mav2)3750self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)37513752self.start_subsubtest("Enable and disable should not affect non-HL links getting HIGH_LATENCY2")3753self.set_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)3754self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)37553756self.run_cmd_enable_high_latency(True)3757self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav),37583759self.run_cmd_enable_high_latency(False)3760self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)3761except Exception as e:3762self.print_exception_caught(e)3763ex = e37643765self.context_pop()37663767self.reboot_sitl()37683769self.set_message_rate_hz("HIGH_LATENCY2", 0)37703771if ex is not None:3772raise ex37733774def download_full_log_list(self, print_logs=True):3775tstart = self.get_sim_time()3776self.mav.mav.log_request_list_send(self.sysid_thismav(),37771, # target component37780,37790xffff)3780logs = {}3781last_id = None3782num_logs = None3783while True:3784now = self.get_sim_time_cached()3785if now - tstart > 5:3786raise NotAchievedException("Did not download list")3787m = self.mav.recv_match(type='LOG_ENTRY',3788blocking=True,3789timeout=1)3790if print_logs:3791self.progress("Received (%s)" % str(m))3792if m is None:3793continue3794logs[m.id] = m3795if last_id is None:3796if m.num_logs == 0:3797# caller to guarantee this works:3798raise NotAchievedException("num_logs is zero")3799num_logs = m.num_logs3800else:3801if m.id != last_id + 1:3802raise NotAchievedException("Sequence not increasing")3803if m.num_logs != num_logs:3804raise NotAchievedException("Number of logs changed")3805if m.time_utc < 1000 and m.id != m.num_logs:3806raise NotAchievedException("Bad timestamp")3807if m.id != m.last_log_num:3808if m.size == 0:3809raise NotAchievedException("Zero-sized log")3810last_id = m.id3811if m.id == m.last_log_num:3812self.progress("Got all logs")3813break38143815# ensure we don't get any extras:3816self.assert_not_receiving_message('LOG_ENTRY', timeout=2)38173818return logs38193820def TestLogDownloadWrap(self):3821"""Test log wrapping."""3822if self.is_tracker():3823# tracker starts armed, which is annoying3824return3825self.progress("Ensuring we have contents we care about")3826self.set_parameter("LOG_FILE_DSRMROT", 1)3827self.set_parameter("LOG_DISARMED", 0)3828self.reboot_sitl()3829logspath = Path("logs")38303831def create_num_logs(num_logs, logsdir, clear_logsdir=True):3832if clear_logsdir:3833shutil.rmtree(logsdir, ignore_errors=True)3834logsdir.mkdir()3835lastlogfile_path = logsdir / Path("LASTLOG.TXT")3836self.progress(f"Add LASTLOG.TXT file with counter at {num_logs}")3837with open(lastlogfile_path, 'w') as lastlogfile:3838lastlogfile.write(f"{num_logs}\n")3839self.progress(f"Create fakelogs from 1 to {num_logs} on logs directory")3840for ii in range(1, num_logs + 1):3841new_log = logsdir / Path(f"{str(ii).zfill(8)}.BIN")3842with open(new_log, 'w+') as logfile:3843logfile.write(f"I AM LOG {ii}\n")3844logfile.write('1' * ii)38453846def verify_logs(test_log_num):3847try:3848wrap = False3849offset = 03850max_logs_num = int(self.get_parameter("LOG_MAX_FILES"))3851if test_log_num > max_logs_num:3852wrap = True3853offset = test_log_num - max_logs_num3854test_log_num = max_logs_num3855logs_dict = self.download_full_log_list(print_logs=False)3856if len(logs_dict) != test_log_num:3857raise NotAchievedException(3858f"Didn't get the full log list, expect {test_log_num} got {len(logs_dict)}")3859self.progress("Checking logs size are matching")3860start_log = offset if wrap else 13861for ii in range(start_log, test_log_num + 1 - offset):3862log_i = logspath / Path(f"{str(ii + offset).zfill(8)}.BIN")3863if logs_dict[ii].size != log_i.stat().st_size:3864logs_dict = self.download_full_log_list(print_logs=False)3865# sometimes we don't have finish writing the log, so get it again prevent failure3866if logs_dict[ii].size != log_i.stat().st_size:3867raise NotAchievedException(3868f"Log{ii} size mismatch : {logs_dict[ii].size} vs {log_i.stat().st_size}"3869)3870if wrap:3871self.progress("Checking wrapped logs size are matching")3872for ii in range(1, offset):3873log_i = logspath / Path(f"{str(ii).zfill(8)}.BIN")3874if logs_dict[test_log_num + 1 - offset + ii].size != log_i.stat().st_size:3875self.progress(f"{logs_dict[test_log_num + 1 - offset + ii]}")3876raise NotAchievedException(3877f"Log{test_log_num + 1 - offset + ii} size mismatch :"3878f" {logs_dict[test_log_num + 1 - offset + ii].size} vs {log_i.stat().st_size}"3879)3880except NotAchievedException as e:3881shutil.rmtree(logspath, ignore_errors=True)3882logspath.mkdir()3883with open(logspath / Path("LASTLOG.TXT"), 'w') as lastlogfile:3884lastlogfile.write("1\n")3885raise e38863887def add_and_verify_log(test_log_num):3888self.wait_ready_to_arm()3889self.arm_vehicle()3890self.delay_sim_time(1)3891self.disarm_vehicle()3892self.delay_sim_time(10)3893verify_logs(test_log_num + 1)38943895def create_and_verify_logs(test_log_num, clear_logsdir=True):3896self.progress(f"Test {test_log_num} logs")3897create_num_logs(test_log_num, logspath, clear_logsdir)3898self.reboot_sitl()3899verify_logs(test_log_num)3900self.start_subsubtest("Adding one more log")3901add_and_verify_log(test_log_num)39023903self.start_subtest("Checking log list match with filesystem info")3904create_and_verify_logs(500)3905create_and_verify_logs(10)3906create_and_verify_logs(1)39073908self.start_subtest("Change LOG_MAX_FILES and Checking log list match with filesystem info")3909self.set_parameter("LOG_MAX_FILES", 250)3910create_and_verify_logs(250)3911self.set_parameter("LOG_MAX_FILES", 1)3912create_and_verify_logs(1)39133914self.start_subtest("Change LOG_MAX_FILES, don't clear old logs and Checking log list match with filesystem info")3915self.set_parameter("LOG_MAX_FILES", 500)3916create_and_verify_logs(500)3917self.set_parameter("LOG_MAX_FILES", 250)3918create_and_verify_logs(250, clear_logsdir=False)39193920# cleanup3921shutil.rmtree(logspath, ignore_errors=True)39223923def TestLogDownload(self):3924"""Test Onboard Log Download."""3925if self.is_tracker():3926# tracker starts armed, which is annoying3927return3928self.progress("Ensuring we have contents we care about")3929self.set_parameter("LOG_FILE_DSRMROT", 1)3930self.set_parameter("LOG_DISARMED", 0)3931self.reboot_sitl()3932original_log_list = self.log_list()3933for i in range(0, 10):3934self.wait_ready_to_arm()3935self.arm_vehicle()3936self.delay_sim_time(1)3937self.disarm_vehicle()3938new_log_list = self.log_list()3939new_log_count = len(new_log_list) - len(original_log_list)3940if new_log_count != 10:3941raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" %3942(new_log_count, original_log_list, new_log_list))3943self.progress("Directory contents: %s" % str(new_log_list))39443945self.download_full_log_list()3946log_id = 53947ofs = 63948count = 23949self.start_subtest("downloading %u bytes from offset %u from log_id %u" %3950(count, ofs, log_id))3951self.mav.mav.log_request_data_send(self.sysid_thismav(),39521, # target component3953log_id,3954ofs,3955count)3956m = self.assert_receive_message('LOG_DATA', timeout=2)3957if m.ofs != ofs:3958raise NotAchievedException("Incorrect offset")3959if m.count != count:3960raise NotAchievedException("Did not get correct number of bytes")3961log_filepath = self.log_filepath(log_id)3962self.progress("Checking against log_filepath (%s)" % str(log_filepath))3963with open(log_filepath, "rb") as bob:3964bob.seek(ofs)3965actual_bytes = bob.read(2)3966actual_bytes = bytearray(actual_bytes)3967if m.data[0] != actual_bytes[0]:3968raise NotAchievedException("Bad first byte got=(0x%02x) want=(0x%02x)" %3969(m.data[0], actual_bytes[0]))3970if m.data[1] != actual_bytes[1]:3971raise NotAchievedException("Bad second byte")39723973log_id = 73974log_filepath = self.log_filepath(log_id)3975self.start_subtest("Downloading log id %u (%s)" % (log_id, log_filepath))3976with open(log_filepath, "rb") as bob:3977actual_bytes = bytearray(bob.read())39783979# get the size first3980self.mav.mav.log_request_list_send(self.sysid_thismav(),39811, # target component3982log_id,3983log_id)3984log_entry = self.assert_receive_message('LOG_ENTRY', timeout=2, verbose=True)3985if log_entry.size != len(actual_bytes):3986raise NotAchievedException("Incorrect bytecount")3987if log_entry.id != log_id:3988raise NotAchievedException("Incorrect log id received")39893990# download the log file in the normal way:3991bytes_to_fetch = 1000003992self.progress("Sending request for %u bytes at offset 0" % (bytes_to_fetch,))3993tstart = self.get_sim_time()3994self.mav.mav.log_request_data_send(3995self.sysid_thismav(),39961, # target component3997log_id,39980,3999bytes_to_fetch4000)4001bytes_to_read = bytes_to_fetch4002if log_entry.size < bytes_to_read:4003bytes_to_read = log_entry.size4004data_downloaded = []4005bytes_read = 04006last_print = 04007while True:4008if bytes_read >= bytes_to_read:4009break4010if self.get_sim_time_cached() - tstart > 120:4011raise NotAchievedException("Did not download log in good time")4012m = self.assert_receive_message('LOG_DATA', timeout=2)4013if m.ofs != bytes_read:4014raise NotAchievedException("Unexpected offset")4015if m.id != log_id:4016raise NotAchievedException("Unexpected id")4017if m.count == 0:4018raise NotAchievedException("Zero bytes read")4019data_downloaded.extend(m.data[0:m.count])4020bytes_read += m.count4021# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4022if time.time() - last_print > 10:4023last_print = time.time()4024self.progress("Read %u/%u" % (bytes_read, bytes_to_read))40254026self.progress("actual_bytes_len=%u data_downloaded_len=%u" %4027(len(actual_bytes), len(data_downloaded)))4028self.assert_bytes_equal(actual_bytes, data_downloaded, maxlen=bytes_to_read)40294030if False:4031bytes_to_read = log_entry.size4032bytes_read = 04033data_downloaded = []4034while bytes_read < bytes_to_read:4035bytes_to_fetch = int(random.random() * 100)4036if bytes_to_fetch > 90:4037bytes_to_fetch = 904038self.progress("Sending request for %u bytes at offset %u" % (bytes_to_fetch, bytes_read))4039self.mav.mav.log_request_data_send(4040self.sysid_thismav(),40411, # target component4042log_id,4043bytes_read,4044bytes_to_fetch4045)4046m = self.assert_receive_message('LOG_DATA', timeout=2)4047self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4048if m.ofs != bytes_read:4049raise NotAchievedException("Incorrect offset in reply want=%u got=%u (%s)" % (bytes_read, m.ofs, str(m)))4050stuff = m.data[0:m.count]4051data_downloaded.extend(stuff)4052bytes_read += m.count4053if len(data_downloaded) != bytes_read:4054raise NotAchievedException("extend fail")40554056if len(actual_bytes) != len(data_downloaded):4057raise NotAchievedException("Incorrect length: disk:%u downloaded: %u" %4058(len(actual_bytes), len(data_downloaded)))4059self.assert_bytes_equal(actual_bytes, data_downloaded)40604061self.start_subtest("Download log backwards")4062bytes_to_read = bytes_to_fetch4063if log_entry.size < bytes_to_read:4064bytes_to_read = log_entry.size4065bytes_read = 04066backwards_data_downloaded = []4067last_print = 04068while bytes_read < bytes_to_read:4069bytes_to_fetch = int(random.random() * 99) + 14070if bytes_to_fetch > 90:4071bytes_to_fetch = 904072if bytes_to_fetch > bytes_to_read - bytes_read:4073bytes_to_fetch = bytes_to_read - bytes_read4074ofs = bytes_to_read - bytes_read - bytes_to_fetch4075# self.progress("bytes_to_read=%u bytes_read=%u bytes_to_fetch=%u ofs=%d" %4076# (bytes_to_read, bytes_read, bytes_to_fetch, ofs))4077self.mav.mav.log_request_data_send(4078self.sysid_thismav(),40791, # target component4080log_id,4081ofs,4082bytes_to_fetch4083)4084m = self.assert_receive_message('LOG_DATA', timeout=2)4085if m.count == 0:4086raise NotAchievedException("xZero bytes read (ofs=%u)" % (ofs,))4087if m.count > bytes_to_fetch:4088raise NotAchievedException("Read too many bytes?!")4089stuff = m.data[0:m.count]4090stuff.extend(backwards_data_downloaded)4091backwards_data_downloaded = stuff4092bytes_read += m.count4093# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4094if time.time() - last_print > 10:4095last_print = time.time()4096self.progress("xRead %u/%u" % (bytes_read, bytes_to_read))40974098self.assert_bytes_equal(actual_bytes, backwards_data_downloaded, maxlen=bytes_to_read)4099# if len(actual_bytes) != len(backwards_data_downloaded):4100# raise NotAchievedException("Size delta: actual=%u vs downloaded=%u" %4101# (len(actual_bytes), len(backwards_data_downloaded)))41024103def download_log(self, log_id, timeout=360):4104tstart = self.get_sim_time()4105data_downloaded = []4106bytes_read = 04107last_print = 04108while True:4109if self.get_sim_time_cached() - tstart > timeout:4110raise NotAchievedException("Did not download log in good time")4111self.mav.mav.log_request_data_send(4112self.sysid_thismav(),41131, # target component4114log_id,4115bytes_read,4116904117)4118m = self.assert_receive_message('LOG_DATA', timeout=2)4119if m.ofs != bytes_read:4120raise NotAchievedException(f"Unexpected offset {bytes_read=} {self.dump_message_verbose(m)}")4121if m.id != log_id:4122raise NotAchievedException(f"Unexpected id {log_id=} {self.dump_message_verbose(m)}")4123data_downloaded.extend(m.data[0:m.count])4124bytes_read += m.count4125if m.count < 90: # FIXME: constant4126break4127# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))4128if time.time() - last_print > 10:4129last_print = time.time()4130self.progress(f"{bytes_read=}")4131return data_downloaded41324133def TestLogDownloadLogRestart(self):4134'''test logging restarts after log download'''4135# self.delay_sim_time(30)4136self.set_parameters({4137"LOG_FILE_RATEMAX": 1,4138})4139self.reboot_sitl()4140number = self.current_onboard_log_number()4141content = self.download_log(number)4142print(f"Content is of length {len(content)}")4143# current_log_filepath = self.current_onboard_log_filepath()4144self.delay_sim_time(5)4145new_number = self.current_onboard_log_number()4146if number == new_number:4147raise NotAchievedException("Did not start logging again")4148new_content = self.download_log(new_number)4149if len(new_content) == 0:4150raise NotAchievedException(f"Unexpected length {len(new_content)=}")41514152#################################################4153# SIM UTILITIES4154#################################################4155def get_sim_time(self, timeout=60, drain_mav=True):4156"""Get SITL time in seconds."""4157if drain_mav:4158self.drain_mav()4159tstart = time.time()4160while True:4161self.drain_all_pexpects()4162if time.time() - tstart > timeout:4163raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)41644165m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=0.1)4166if m is None:4167continue4168if m.get_srcSystem() != self.sysid_thismav():4169continue41704171return m.time_boot_ms * 1.0e-341724173def get_sim_time_cached(self):4174"""Get SITL time in seconds."""4175x = self.mav.messages.get("SYSTEM_TIME", None)4176if x is None:4177raise NotAchievedException("No cached time available (%s)" % (self.mav.sysid,))4178ret = x.time_boot_ms * 1.0e-34179if ret != self.last_sim_time_cached:4180self.last_sim_time_cached = ret4181self.last_sim_time_cached_wallclock = time.time()4182else:4183timeout = 304184if self.valgrind:4185timeout *= 104186if time.time() - self.last_sim_time_cached_wallclock > timeout and not self.gdb:4187raise AutoTestTimeoutException("sim_time_cached is not updating!")4188return ret41894190def sim_location(self):4191"""Return current simulator location."""4192m = self.assert_receive_message('SIMSTATE')4193return mavutil.location(m.lat*1.0e-7,4194m.lng*1.0e-7,41950,4196math.degrees(m.yaw))41974198def sim_location_int(self):4199"""Return current simulator location."""4200m = self.assert_receive_message('SIMSTATE')4201return mavutil.location(m.lat,4202m.lng,42030,4204math.degrees(m.yaw))42054206def save_wp(self, ch=7):4207"""Trigger RC Aux to save waypoint."""4208self.set_rc(ch, 1000)4209self.delay_sim_time(1)4210self.set_rc(ch, 2000)4211self.delay_sim_time(1)4212self.set_rc(ch, 1000)4213self.delay_sim_time(1)42144215def correct_wp_seq_numbers(self, wps):4216# renumber the items:4217count = 04218for item in wps:4219item.seq = count4220count += 142214222def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1):4223return self.create_simple_relloc_mission(4224self.home_position_as_mav_location(),4225items_in,4226target_system=target_system,4227target_component=target_component,4228)42294230def create_simple_relloc_mission(self, loc, 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:4255relloc = self.offset_location_ne(loc, n, e)4256lat = relloc.lat4257lng = relloc.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')4263p1 = opts.get('p1', 0) # should we pass `None` instead?4264ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, p1=p1, x=int(lat*1e7), y=int(lng*1e7), z=alt))4265seq += 142664267return ret42684269def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):4270mission = self.create_simple_relhome_mission(4271items,4272target_system=target_system,4273target_component=target_component)4274self.check_mission_upload_download(mission)42754276def upload_simple_relloc_mission(self, loc, items, target_system=1, target_component=1):4277mission = self.create_simple_relloc_mission(4278loc,4279items,4280target_system=target_system,4281target_component=target_component)4282self.check_mission_upload_download(mission)42834284def start_flying_simple_relhome_mission(self, items):4285'''uploads items, changes mode to auto, waits ready to arm and arms4286vehicle. If the first item it a takeoff you can expect the4287vehicle to fly after this method returns. On Copter AUTO_OPTIONS4288should be 3.4289'''42904291self.upload_simple_relhome_mission(items)4292self.set_current_waypoint(0, check_afterwards=False)42934294self.change_mode('AUTO')4295self.wait_ready_to_arm()42964297self.arm_vehicle()4298# copter gets stuck in auto; if you run a mission to4299# completion then the mission state machine ends up in a4300# "done" state and you can't restart by just setting an4301# earlier waypoint:4302self.send_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)43034304def fly_simple_relhome_mission(self, items):4305'''uploads items, changes mode to auto, waits ready to arm and arms4306vehicle. Then waits for the vehicle to disarm.4307'''4308self.start_flying_simple_relhome_mission(items)4309self.wait_disarmed()43104311def get_mission_count(self):4312return self.get_parameter("MIS_TOTAL")43134314def run_auxfunc(self,4315function,4316level,4317run_cmd=None,4318want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):4319if run_cmd is None:4320run_cmd = self.run_cmd4321run_cmd(4322mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,4323p1=function,4324p2=level,4325want_result=want_result,4326)43274328def assert_mission_count(self, expected):4329count = self.get_mission_count()4330if count != expected:4331raise NotAchievedException("Unexpected count got=%u want=%u" %4332(count, expected))43334334def clear_wp(self, ch=8):4335"""Trigger RC Aux to clear waypoint."""4336self.progress("Clearing waypoints")4337self.set_rc(ch, 1000)4338self.delay_sim_time(0.5)4339self.set_rc(ch, 2000)4340self.delay_sim_time(0.5)4341self.set_rc(ch, 1000)4342self.assert_mission_count(0)43434344def log_list(self):4345'''return a list of log files present in POSIX-style logging dir'''4346ret = sorted(glob.glob("logs/00*.BIN"))4347self.progress("log list: %s" % str(ret))4348return ret43494350def assert_parameter_values(self, parameters, epsilon=None):4351names = parameters.keys()4352got = self.get_parameters(names)4353for name in names:4354equal = got[name] == parameters[name]4355if epsilon is not None:4356delta = abs(got[name] - parameters[name])4357equal = delta <= epsilon4358if not equal:4359raise NotAchievedException("parameter %s want=%f got=%f" %4360(name, parameters[name], got[name]))4361self.progress("%s has expected value %f" % (name, got[name]))43624363def assert_parameter_value(self, parameter, required, **kwargs):4364self.assert_parameter_values({4365parameter: required,4366}, **kwargs)43674368def assert_reach_imu_temperature(self, target, timeout):4369'''wait to reach a target temperature'''4370tstart = self.get_sim_time()4371temp_ok = False4372last_print_temp = -1004373while self.get_sim_time_cached() - tstart < timeout:4374m = self.assert_receive_message('RAW_IMU', timeout=2)4375temperature = m.temperature*0.014376if temperature >= target:4377self.progress("Reached temperature %.1f" % temperature)4378temp_ok = True4379break4380if temperature - last_print_temp > 1:4381self.progress("temperature %.1f" % temperature)4382last_print_temp = temperature43834384if not temp_ok:4385raise NotAchievedException("target temperature")43864387def message_has_field_values_field_values_equal(self, fieldname, value, got, epsilon=None):4388if isinstance(value, float):4389if math.isnan(value) or math.isnan(got):4390return math.isnan(value) and math.isnan(got)43914392if type(value) is not str and epsilon is not None:4393return abs(got - value) <= epsilon43944395return got == value43964397def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None):4398for (fieldname, value) in fieldvalues.items():4399if "[" in fieldname: # fieldname == "arrayname[index]"4400assert fieldname[-1] == "]", fieldname4401arrayname, index = fieldname.split("[", 1)4402index = int(index[:-1])4403got = getattr(m, arrayname)[index]4404else:4405got = getattr(m, fieldname)44064407value_string = value4408got_string = got4409enum_name = m.fieldenums_by_name.get(fieldname, None)4410if enum_name is not None:4411enum = mavutil.mavlink.enums[enum_name]4412if getattr(enum, "bitmask", None):4413value_strings = []4414value_copy = value4415shift_value = 14416while value_copy != 0:4417if value_copy & 0x1:4418value_strings.append(enum[shift_value].name)4419else:4420value_strings.append("!" + enum[shift_value].name)4421shift_value += 14422value_copy = value_copy >> 14423value_string = f"{value_string} {'|'.join(value_strings)}"4424elif enum_name != 'AIRSPEED_SENSOR_FLAGS':4425# once the ".bitmask" attribute on enumerations4426# becomes uniquitous the check the4427# AIRSPEED_SENSOR_FLAGS can be removed.4428if value not in enum:4429raise ValueError(f"Expected value {value} not in enum {enum}")4430if got not in enum:4431raise ValueError(f"Received value {got} not in enum {enum}")4432value_string = f"{value} ({enum[value].name})"4433got_string = f"{got} ({enum[got].name})"44344435if not self.message_has_field_values_field_values_equal(4436fieldname, value, got, epsilon=epsilon4437):4438# see if this is an enumerated field:4439self.progress(self.dump_message_verbose(m))4440self.progress("Expected %s.%s to be %s, got %s" %4441(m.get_type(), fieldname, value_string, got_string))4442return False4443if verbose:4444self.progress("%s.%s has expected value %s" %4445(m.get_type(), fieldname, value_string))4446return True44474448def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):4449if self.message_has_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon):4450return4451raise NotAchievedException("Did not get expected field values")44524453def assert_cached_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None):4454'''checks the most-recently received instance of message to ensure it4455has the correct field values'''4456m = self.get_cached_message(message)4457self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)4458return m44594460def assert_received_message_field_values(self,4461message,4462fieldvalues,4463verbose=True,4464very_verbose=False,4465epsilon=None,4466poll=False,4467timeout=None,4468check_context=False,4469):4470if poll:4471self.poll_message(message)4472m = self.assert_receive_message(4473message,4474verbose=verbose,4475very_verbose=very_verbose,4476timeout=timeout,4477check_context=check_context4478)4479self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)4480return m44814482# FIXME: try to use wait_and_maintain here?4483def wait_message_field_values(self,4484message,4485fieldvalues,4486timeout=10,4487epsilon=None,4488instance=None,4489minimum_duration=None,4490verbose=False,4491very_verbose=False,4492):44934494tstart = self.get_sim_time_cached()4495pass_start = None4496last_debug = 04497while True:4498now = self.get_sim_time_cached()4499if now - tstart > timeout:4500raise NotAchievedException("Field never reached values")4501m = self.assert_receive_message(4502message,4503instance=instance,4504verbose=verbose,4505very_verbose=very_verbose,4506)4507if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose):4508if minimum_duration is not None:4509if pass_start is None:4510pass_start = now4511continue4512delta = now - pass_start4513if now - last_debug >= 1:4514last_debug = now4515self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)")4516if delta < minimum_duration:4517continue4518else:4519self.progress("Reached field values")4520return m4521pass_start = None45224523def onboard_logging_not_log_disarmed(self):4524self.start_subtest("Test LOG_DISARMED-is-false behaviour")4525self.set_parameter("LOG_DISARMED", 0)4526self.set_parameter("LOG_FILE_DSRMROT", 0)4527self.reboot_sitl()4528self.wait_ready_to_arm() # let things setttle4529self.start_subtest("Ensure setting LOG_DISARMED yields a new file")4530original_list = self.log_list()4531self.progress("original list: %s" % str(original_list))4532self.set_parameter("LOG_DISARMED", 1)4533self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4534new_list = self.log_list()4535self.progress("new list: %s" % str(new_list))4536if len(new_list) - len(original_list) != 1:4537raise NotAchievedException("Got more than one new log")4538self.set_parameter("LOG_DISARMED", 0)4539self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4540new_list = self.log_list()4541if len(new_list) - len(original_list) != 1:4542raise NotAchievedException("Got more or less than one new log after toggling LOG_DISARMED off")45434544self.start_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")4545self.set_parameter("LOG_DISARMED", 1)4546self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4547new_new_list = self.log_list()4548if len(new_new_list) != len(new_list):4549raise NotAchievedException("Got extra files when toggling LOG_DISARMED")4550self.set_parameter("LOG_DISARMED", 0)4551self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code4552new_new_list = self.log_list()4553if len(new_new_list) != len(new_list):4554raise NotAchievedException("Got extra files when toggling LOG_DISARMED to 0 again")4555self.end_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")45564557self.start_subtest("Check disarm rot when log disarmed is zero")4558self.assert_parameter_value("LOG_DISARMED", 0)4559self.set_parameter("LOG_FILE_DSRMROT", 1)4560old_speedup = self.get_parameter("SIM_SPEEDUP")4561# reduce speedup to reduce chance of race condition here4562self.set_parameter("SIM_SPEEDUP", 1)4563pre_armed_list = self.log_list()4564if self.is_copter() or self.is_heli():4565self.set_parameter("DISARM_DELAY", 0)4566self.arm_vehicle()4567post_armed_list = self.log_list()4568if len(post_armed_list) != len(pre_armed_list):4569raise NotAchievedException("Got unexpected new log")4570self.disarm_vehicle()4571old_speedup = self.set_parameter("SIM_SPEEDUP", old_speedup)4572post_disarmed_list = self.log_list()4573if len(post_disarmed_list) != len(post_armed_list):4574raise NotAchievedException("Log rotated immediately")4575self.progress("Allowing time for post-disarm-logging to occur if it will")4576self.delay_sim_time(5)4577post_disarmed_post_delay_list = self.log_list()4578if len(post_disarmed_post_delay_list) != len(post_disarmed_list):4579raise NotAchievedException("Got log rotation when we shouldn't have")4580self.progress("Checking that arming does produce a new log")4581self.arm_vehicle()4582post_armed_list = self.log_list()4583if len(post_armed_list) - len(post_disarmed_post_delay_list) != 1:4584raise NotAchievedException("Did not get new log for rotation")4585self.progress("Now checking natural rotation after HAL_LOGGER_ARM_PERSIST")4586self.disarm_vehicle()4587post_disarmed_list = self.log_list()4588if len(post_disarmed_list) != len(post_armed_list):4589raise NotAchievedException("Log rotated immediately")4590self.delay_sim_time(30)4591delayed_post_disarmed_list = self.log_list()4592# should *still* not get another log as LOG_DISARMED is false4593if len(post_disarmed_list) != len(delayed_post_disarmed_list):4594self.progress("Unexpected new log found")45954596def onboard_logging_log_disarmed(self):4597self.start_subtest("Test LOG_DISARMED-is-true behaviour")4598start_list = self.log_list()4599self.set_parameter("LOG_FILE_DSRMROT", 0)4600self.set_parameter("LOG_DISARMED", 0)4601self.reboot_sitl()4602restart_list = self.log_list()4603if len(start_list) != len(restart_list):4604raise NotAchievedException(4605"Unexpected log detected (pre-delay) initial=(%s) restart=(%s)" %4606(str(sorted(start_list)), str(sorted(restart_list))))4607self.delay_sim_time(20)4608restart_list = self.log_list()4609if len(start_list) != len(restart_list):4610raise NotAchievedException("Unexpected log detected (post-delay)")4611self.set_parameter("LOG_DISARMED", 1)4612self.delay_sim_time(5) # LOG_DISARMED is polled4613post_log_disarmed_set_list = self.log_list()4614if len(post_log_disarmed_set_list) == len(restart_list):4615raise NotAchievedException("Did not get new log when LOG_DISARMED set")4616self.progress("Ensuring we get a new log after a reboot")4617self.reboot_sitl()4618self.delay_sim_time(5)4619post_reboot_log_list = self.log_list()4620if len(post_reboot_log_list) == len(post_log_disarmed_set_list):4621raise NotAchievedException("Did not get fresh log-disarmed log after a reboot")4622self.progress("Ensuring no log rotation when we toggle LOG_DISARMED off then on again")4623self.set_parameter("LOG_DISARMED", 0)4624current_log_filepath = self.current_onboard_log_filepath()4625self.delay_sim_time(10) # LOG_DISARMED is polled4626post_toggleoff_list = self.log_list()4627if len(post_toggleoff_list) != len(post_reboot_log_list):4628raise NotAchievedException("Shouldn't get new file yet")4629self.progress("Ensuring log does not grow when LOG_DISARMED unset...")4630current_log_filepath_size = os.path.getsize(current_log_filepath)4631self.delay_sim_time(5)4632current_log_filepath_new_size = os.path.getsize(current_log_filepath)4633if current_log_filepath_new_size != current_log_filepath_size:4634raise NotAchievedException(4635"File growing after LOG_DISARMED unset (new=%u old=%u" %4636(current_log_filepath_new_size, current_log_filepath_size))4637self.progress("Turning LOG_DISARMED back on again")4638self.set_parameter("LOG_DISARMED", 1)4639self.delay_sim_time(5) # LOG_DISARMED is polled4640post_toggleon_list = self.log_list()4641if len(post_toggleon_list) != len(post_toggleoff_list):4642raise NotAchievedException("Log rotated when it shouldn't")4643self.progress("Checking log is now growing again")4644if os.path.getsize(current_log_filepath) == current_log_filepath_size:4645raise NotAchievedException("Log is not growing")46464647# self.progress("Checking LOG_FILE_DSRMROT behaviour when log_DISARMED set")4648# self.set_parameter("LOG_FILE_DSRMROT", 1)4649# self.wait_ready_to_arm()4650# pre = self.log_list()4651# self.arm_vehicle()4652# post = self.log_list()4653# if len(pre) != len(post):4654# raise NotAchievedException("Rotation happened on arming?!")4655# size_a = os.path.getsize(current_log_filepath)4656# self.delay_sim_time(5)4657# size_b = os.path.getsize(current_log_filepath)4658# if size_b <= size_a:4659# raise NotAchievedException("Log not growing")4660# self.disarm_vehicle()4661# instant_post_disarm_list = self.log_list()4662# self.progress("Should not rotate straight away")4663# if len(instant_post_disarm_list) != len(post):4664# raise NotAchievedException("Should not rotate straight away")4665# self.delay_sim_time(20)4666# post_disarm_list = self.log_list()4667# if len(post_disarm_list) - len(instant_post_disarm_list) != 1:4668# raise NotAchievedException("Did not get exactly one more log")46694670# self.progress("If we re-arm during the HAL_LOGGER_ARM_PERSIST period it should rotate")46714672def onboard_logging_forced_arm(self):4673'''ensure a bug where we didn't start logging when arming was forced4674does not reappear'''4675self.start_subtest("Ensure we get a log when force-arming")4676self.set_parameter("LOG_DISARMED", 0)4677self.reboot_sitl() # so we'll definitely start a log on arming4678pre_arming_list = self.log_list()4679self.wait_ready_to_arm()4680self.arm_vehicle(force=True)4681# we might be relying on a thread to actually create the log4682# file when doing forced-arming; give the file time to appear:4683self.delay_sim_time(10)4684post_arming_list = self.log_list()4685self.disarm_vehicle()4686if len(post_arming_list) <= len(pre_arming_list):4687raise NotAchievedException("Did not get a log on forced arm")46884689def Logging(self):4690'''Test Onboard Logging'''4691if self.is_tracker():4692return4693self.onboard_logging_forced_arm()4694self.onboard_logging_log_disarmed()4695self.onboard_logging_not_log_disarmed()46964697def LoggingFormatSanityChecks(self, path):4698dfreader = self.dfreader_for_path(path)4699first_message = dfreader.recv_match()4700if first_message.get_type() != 'FMT':4701raise NotAchievedException("Expected first message to be a FMT message")4702if first_message.Name != 'FMT':4703raise NotAchievedException("Expected first message to be the FMT FMT message")47044705self.progress("Ensuring DCM format is received") # it's a WriteStreaming message...4706while True:4707m = dfreader.recv_match(type='FMT')4708if m is None:4709raise NotAchievedException("Did not find DCM format")4710if m.Name != 'DCM':4711continue4712self.progress("Found DCM format")4713break47144715self.progress("No message should appear before its format")4716dfreader.rewind()4717seen_formats = set()4718while True:4719m = dfreader.recv_match()4720if m is None:4721break4722m_type = m.get_type()4723if m_type == 'FMT':4724seen_formats.add(m.Name)4725continue4726if m_type not in seen_formats:4727raise ValueError(f"{m_type} seen before its format")4728# print(f"{m_type} OK")47294730def LoggingFormat(self):4731'''ensure formats are emitted appropriately'''47324733self.context_push()4734self.set_parameter('LOG_FILE_DSRMROT', 1)4735self.wait_ready_to_arm()4736for i in range(3):4737self.arm_vehicle()4738self.delay_sim_time(5)4739path = self.current_onboard_log_filepath()4740self.disarm_vehicle()4741self.LoggingFormatSanityChecks(path)4742self.context_pop()47434744self.context_push()4745for i in range(3):4746self.set_parameter("LOG_DISARMED", 1)4747self.reboot_sitl()4748self.delay_sim_time(5)4749path = self.current_onboard_log_filepath()4750self.set_parameter("LOG_DISARMED", 0)4751self.LoggingFormatSanityChecks(path)4752self.context_pop()47534754def TestLogDownloadMAVProxy(self, upload_logs=False):4755"""Download latest log."""4756filename = "MAVProxy-downloaded-log.BIN"4757mavproxy = self.start_mavproxy()4758self.mavproxy_load_module(mavproxy, 'log')4759self.set_parameter('SIM_SPEEDUP', 1)4760mavproxy.send("log list\n")4761mavproxy.expect("numLogs")4762self.wait_heartbeat()4763self.wait_heartbeat()4764mavproxy.send("set shownoise 0\n")4765mavproxy.send("log download latest %s\n" % filename)4766mavproxy.expect("Finished downloading", timeout=120)4767self.mavproxy_unload_module(mavproxy, 'log')4768self.stop_mavproxy(mavproxy)47694770def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):4771"""Download latest log over network port"""4772self.context_push()4773self.set_parameters({4774"NET_ENABLE": 1,4775"LOG_DISARMED": 0,4776"LOG_DARM_RATEMAX": 1, # make small logs4777# UDP client4778"NET_P1_TYPE": 1,4779"NET_P1_PROTOCOL": 2,4780"NET_P1_PORT": 16001,4781"NET_P1_IP0": 127,4782"NET_P1_IP1": 0,4783"NET_P1_IP2": 0,4784"NET_P1_IP3": 1,4785# UDP server4786"NET_P2_TYPE": 2,4787"NET_P2_PROTOCOL": 2,4788"NET_P2_PORT": 16002,4789"NET_P2_IP0": 0,4790"NET_P2_IP1": 0,4791"NET_P2_IP2": 0,4792"NET_P2_IP3": 0,4793# TCP client4794"NET_P3_TYPE": 3,4795"NET_P3_PROTOCOL": 2,4796"NET_P3_PORT": 16003,4797"NET_P3_IP0": 127,4798"NET_P3_IP1": 0,4799"NET_P3_IP2": 0,4800"NET_P3_IP3": 1,4801# TCP server4802"NET_P4_TYPE": 4,4803"NET_P4_PROTOCOL": 2,4804"NET_P4_PORT": 16004,4805"NET_P4_IP0": 0,4806"NET_P4_IP1": 0,4807"NET_P4_IP2": 0,4808"NET_P4_IP3": 0,4809})4810self.reboot_sitl()48114812# ensure the latest log file is very small:4813self.context_push()4814self.set_parameter('LOG_DISARMED', 1)4815self.delay_sim_time(15)4816self.progress(f"Current onboard log filepath {self.current_onboard_log_filepath()}")4817self.context_pop()48184819# ensure that the autopilot has a timestamp on that file by4820# now, or MAVProxy does not see it as the latest log:4821self.wait_gps_fix_type_gte(3)48224823self.set_parameter('SIM_SPEEDUP', 1)48244825endpoints = [('UDPClient', ':16001') ,4826('UDPServer', 'udpout:127.0.0.1:16002'),4827('TCPClient', 'tcpin:0.0.0.0:16003'),4828('TCPServer', 'tcp:127.0.0.1:16004')]4829for name, e in endpoints:4830self.progress("Downloading log with %s %s" % (name, e))4831filename = "MAVProxy-downloaded-net-log-%s.BIN" % name48324833mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])4834self.mavproxy_load_module(mavproxy, 'log')4835self.wait_heartbeat()4836mavproxy.send("log list\n")4837mavproxy.expect("numLogs")4838# ensure the full list of logs has come out4839for i in range(5):4840self.wait_heartbeat()4841mavproxy.send("log download latest %s\n" % filename)4842mavproxy.expect("Finished downloading", timeout=120)4843self.mavproxy_unload_module(mavproxy, 'log')4844self.stop_mavproxy(mavproxy)48454846self.set_parameters({4847# multicast UDP client4848"NET_P1_TYPE": 1,4849"NET_P1_PROTOCOL": 2,4850"NET_P1_PORT": 16005,4851"NET_P1_IP0": 239,4852"NET_P1_IP1": 255,4853"NET_P1_IP2": 145,4854"NET_P1_IP3": 50,4855# Broadcast UDP client4856"NET_P2_TYPE": 1,4857"NET_P2_PROTOCOL": 2,4858"NET_P2_PORT": 16006,4859"NET_P2_IP0": 255,4860"NET_P2_IP1": 255,4861"NET_P2_IP2": 255,4862"NET_P2_IP3": 255,4863"NET_P3_TYPE": -1,4864"NET_P4_TYPE": -1,4865"LOG_DISARMED": 0,4866})4867self.reboot_sitl()48684869self.set_parameter('SIM_SPEEDUP', 1)48704871endpoints = [('UDPMulticast', 'mcast:16005') ,4872('UDPBroadcast', ':16006')]4873for name, e in endpoints:4874self.progress("Downloading log with %s %s" % (name, e))4875filename = "MAVProxy-downloaded-net-log-%s.BIN" % name48764877mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])4878self.mavproxy_load_module(mavproxy, 'log')4879self.wait_heartbeat()4880mavproxy.send("log list\n")4881mavproxy.expect("numLogs")4882# ensure the full list of logs has come out4883for i in range(5):4884self.wait_heartbeat()4885mavproxy.send("log download latest %s\n" % filename)4886mavproxy.expect("Finished downloading", timeout=120)4887self.mavproxy_unload_module(mavproxy, 'log')4888self.stop_mavproxy(mavproxy)48894890self.context_pop()48914892def TestLogDownloadMAVProxyCAN(self, upload_logs=False):4893"""Download latest log over CAN serial port"""4894self.context_push()4895self.set_parameters({4896"CAN_P1_DRIVER": 1,4897"LOG_DISARMED": 1,4898})4899self.reboot_sitl()4900self.set_parameters({4901"CAN_D1_UC_SER_EN": 1,4902"CAN_D1_UC_S1_NOD": 125,4903"CAN_D1_UC_S1_IDX": 4,4904"CAN_D1_UC_S1_BD": 57600,4905"CAN_D1_UC_S1_PRO": 2,4906})4907self.reboot_sitl()49084909self.set_parameter('SIM_SPEEDUP', 1)49104911filename = "MAVProxy-downloaded-can-log.BIN"4912# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:155504913mavproxy = self.start_mavproxy(master=':15550')4914mavproxy.expect("Detected vehicle")4915self.mavproxy_load_module(mavproxy, 'log')4916mavproxy.send("log list\n")4917mavproxy.expect("numLogs")4918# ensure the full list of logs has come out4919for i in range(5):4920self.wait_heartbeat()4921mavproxy.send("set shownoise 0\n")4922mavproxy.send("log download latest %s\n" % filename)4923mavproxy.expect("Finished downloading", timeout=120)4924self.mavproxy_unload_module(mavproxy, 'log')4925self.stop_mavproxy(mavproxy)4926self.context_pop()49274928def show_gps_and_sim_positions(self, on_off):4929"""Allow to display gps and actual position on map."""4930if on_off is True:4931# turn on simulator display of gps and actual position4932self.mavproxy.send('map set showgpspos 1\n')4933self.mavproxy.send('map set showsimpos 1\n')4934else:4935# turn off simulator display of gps and actual position4936self.mavproxy.send('map set showgpspos 0\n')4937self.mavproxy.send('map set showsimpos 0\n')49384939@staticmethod4940def mission_count(filename):4941"""Load a mission from a file and return number of waypoints."""4942wploader = mavwp.MAVWPLoader()4943wploader.load(filename)4944return wploader.count()49454946def install_message_hook(self, hook):4947self.message_hooks.append(hook)49484949def install_message_hook_context(self, hook):4950'''installs a message hook which will be removed when the context goes4951away'''4952if self.mav is None:4953return4954self.message_hooks.append(hook)4955self.context_get().message_hooks.append(hook)49564957def remove_message_hook(self, hook):4958'''remove hook from list of message hooks. Assumes it exists exactly4959once'''4960if self.mav is None:4961return4962self.message_hooks.remove(hook)4963if isinstance(hook, TestSuite.MessageHook):4964hook.hook_removed()49654966def install_script_content_context(self, scriptname, content):4967'''installs an example script with content which will be4968removed when the context goes away4969'''4970self.install_script_content(scriptname, content)4971self.context_get().installed_scripts.append(scriptname)49724973def install_example_script_context(self, scriptname):4974'''installs an example script which will be removed when the context goes4975away'''4976self.install_example_script(scriptname)4977self.context_get().installed_scripts.append(scriptname)49784979def install_test_script_context(self, scriptnames):4980'''installs an test script which will be removed when the context goes4981away'''4982if isinstance(scriptnames, str):4983scriptnames = [scriptnames]4984for scriptname in scriptnames:4985self.install_test_script(scriptname)4986self.context_get().installed_scripts.extend(scriptnames)49874988def install_test_scripts_context(self, *args, **kwargs):4989'''same as install_test_scripts_context - just pluralised name'''4990return self.install_test_script_context(*args, **kwargs)49914992def install_test_modules_context(self):4993'''installs test modules which will be removed when the context goes4994away'''4995self.install_test_modules()4996self.context_get().installed_modules.append("test")49974998def install_mavlink_module_context(self):4999'''installs mavlink module which will be removed when the context goes5000away'''5001self.install_mavlink_module()5002self.context_get().installed_modules.append("mavlink")50035004def install_applet_script_context(self, scriptname, **kwargs):5005'''installs an applet script which will be removed when the context goes5006away'''5007self.install_applet_script(scriptname, **kwargs)5008self.context_get().installed_scripts.append(scriptname)50095010def rootdir(self):5011this_dir = os.path.dirname(__file__)5012return os.path.realpath(os.path.join(this_dir, "../.."))50135014def ardupilot_stores_frame_for_cmd(self, t):5015# ardupilot doesn't remember frame on these commands5016return t not in [5017mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,5018mavutil.mavlink.MAV_CMD_CONDITION_YAW,5019mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,5020mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,5021mavutil.mavlink.MAV_CMD_DO_JUMP,5022mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,5023mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,5024mavutil.mavlink.MAV_CMD_DO_SET_SERVO,5025mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,5026]50275028def assert_mission_files_same(self, file1, file2, match_comments=False):5029self.progress("Comparing (%s) and (%s)" % (file1, file2, ))50305031f1 = open(file1)5032f2 = open(file2)5033lines1 = f1.readlines()5034lines2 = f2.readlines()50355036if not match_comments:5037# strip comments from all lines5038lines1 = [re.sub(r"\s*#.*", "", x) for x in lines1]5039lines2 = [re.sub(r"\s*#.*", "", x) for x in lines2]5040lines1 = [x.rstrip() for x in lines1]5041lines2 = [x.rstrip() for x in lines2]5042# remove now-empty lines:5043lines1 = filter(lambda x: len(x), lines1)5044lines2 = filter(lambda x: len(x), lines2)50455046for l1, l2 in zip(lines1, lines2):5047l1 = l1.rstrip("\r\n")5048l2 = l2.rstrip("\r\n")5049if l1 == l2:5050# e.g. the first "QGC WPL 110" line5051continue5052if re.match(r"0\s", l1):5053# home changes...5054continue5055l1 = l1.rstrip()5056l2 = l2.rstrip()5057fields1 = re.split(r"\s+", l1)5058fields2 = re.split(r"\s+", l2)5059# line = int(fields1[0])5060t = int(fields1[3]) # mission item type5061for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):5062if count == 2: # frame5063if not self.ardupilot_stores_frame_for_cmd(t):5064if int(i1) in [3, 10]: # 3 is relative, 10 is terrain5065i1 = 05066if int(i2) in [3, 10]:5067i2 = 05068if count == 6: # param 35069if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:5070# ardupilot canonicalises this to -1 for ccw or 1 for cw.5071if float(i1) == 0:5072i1 = 1.05073if float(i2) == 0:5074i2 = 1.05075if count == 7: # param 45076if t == mavutil.mavlink.MAV_CMD_NAV_LAND:5077# ardupilot canonicalises "0" to "1" param 4 (yaw)5078if int(float(i1)) == 0:5079i1 = 15080if int(float(i2)) == 0:5081i2 = 15082if 0 <= count <= 3 or 11 <= count <= 11:5083if int(i1) != int(i2):5084raise ValueError("Files have different content: (%s vs %s) (%s vs %s) (%d vs %d) (count=%u)" %5085(file1, file2, l1, l2, int(i1), int(i2), count)) # NOCI5086continue5087if 4 <= count <= 10:5088f_i1 = float(i1)5089f_i2 = float(i2)5090delta = abs(f_i1 - f_i2)5091max_allowed_delta = 0.0000095092if delta > max_allowed_delta:5093raise ValueError(5094("Files have different (float) content: " +5095"(%s) and (%s) " +5096"(%s vs %s) " +5097"(%f vs %f) " +5098"(%.10f) " +5099"(count=%u)") %5100(file1, file2,5101l1, l2,5102f_i1, f_i2,5103delta,5104count)) # NOCI5105continue5106raise ValueError("count %u not handled" % count)5107self.progress("Files same")51085109def assert_not_receive_message(self, message, timeout=1, mav=None, condition=None):5110'''this is like assert_not_receiving_message but uses sim time not5111wallclock time'''5112self.progress("making sure we're not getting %s messages" % message)5113if mav is None:5114mav = self.mav51155116tstart = self.get_sim_time_cached()5117while True:5118m = mav.recv_match(type=message, blocking=True, timeout=0.1, condition=condition)5119if m is not None:5120self.progress("Received: %s" % self.dump_message_verbose(m))5121raise PreconditionFailedException("Receiving %s messages" % message)5122if mav != self.mav:5123# update timestamp....5124self.drain_mav(self.mav)5125if self.get_sim_time_cached() - tstart > timeout:5126return51275128def assert_receive_message(self,5129type,5130timeout=None,5131verbose=False,5132very_verbose=False,5133mav=None,5134condition=None,5135delay_fn=None,5136instance=None,5137check_context=False):5138if timeout is None:5139timeout = 15140if mav is None:5141mav = self.mav51425143if check_context:5144collection = self.context_collection(type)5145if len(collection) > 0:5146# return the most-recently-received message:5147return collection[-1]51485149m = None5150tstart = time.time() # timeout in wallclock5151while True:5152m = mav.recv_match(type=type, blocking=True, timeout=0.05, condition=condition)5153if instance is not None:5154if getattr(m, m._instance_field) != instance:5155continue5156if m is not None:5157break5158elapsed_time = time.time() - tstart5159if elapsed_time > timeout:5160raise NotAchievedException("Did not get %s after %s seconds" %5161(type, elapsed_time))5162if delay_fn is not None:5163delay_fn()5164if verbose:5165self.progress("Received (%s)" % str(m))5166if very_verbose:5167self.progress(self.dump_message_verbose(m))5168return m51695170def assert_receive_named_value_float(self, name, timeout=10):5171tstart = self.get_sim_time_cached()5172while True:5173if self.get_sim_time_cached() - tstart > timeout:5174raise NotAchievedException("Did not get NAMED_VALUE_FLOAT %s" % name)5175m = self.assert_receive_message('NAMED_VALUE_FLOAT', verbose=1, very_verbose=1, timeout=timeout)5176if m.name != name:5177continue5178return m51795180def assert_receive_named_value_float_value(self, name, value, epsilon=0.0001, timeout=10):5181m = self.assert_receive_named_value_float_value(name, timeout=timeout)5182if abs(m.value - value) > epsilon:5183raise NotAchievedException("Bad %s want=%f got=%f" % (name, value, m.value))51845185def assert_rally_files_same(self, file1, file2):5186self.progress("Comparing (%s) and (%s)" % (file1, file2, ))5187f1 = open(file1)5188f2 = open(file2)5189lines_f1 = f1.readlines()5190lines_f2 = f2.readlines()5191self.assert_rally_content_same(lines_f1, lines_f2)51925193def assert_rally_filepath_content(self, file1, content):5194f1 = open(file1)5195lines_f1 = f1.readlines()5196lines_content = content.split("\n")5197print("lines content: %s" % str(lines_content))5198self.assert_rally_content_same(lines_f1, lines_content)51995200def assert_rally_content_same(self, f1, f2):5201'''check each line in f1 matches one-to-one with f2'''5202for l1, l2 in zip(f1, f2):5203print("l1: %s" % l1)5204print("l2: %s" % l2)5205l1 = l1.rstrip("\n")5206l2 = l2.rstrip("\n")5207l1 = l1.rstrip("\r")5208l2 = l2.rstrip("\r")5209if l1 == l2:5210# e.g. the first "QGC WPL 110" line5211continue5212l1 = l1.rstrip()5213l2 = l2.rstrip()5214print("al1: %s" % str(l1))5215print("al2: %s" % str(l2))5216fields1 = re.split(r"\s+", l1)5217fields2 = re.split(r"\s+", l2)5218# line = int(fields1[0])5219# t = int(fields1[3]) # mission item type5220for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):5221self.progress(f"{count=} {i1=} {i2=}")5222if 0 <= count <= 3 or 11 <= count <= 11:5223if int(i1) != int(i2):5224raise ValueError(5225"Rally points different: "5226f"({l1} vs {l2}) " +5227f"{int(i1)} vs {int(i2)}) " +5228f"({count=}))"5229)5230continue5231if 4 <= count <= 10:5232f_i1 = float(i1)5233f_i2 = float(i2)5234delta = abs(f_i1 - f_i2)5235max_allowed_delta = 0.0000095236self.progress(f"{count=} {f_i1=} {f_i2=}")5237if delta > max_allowed_delta:5238raise ValueError(5239"Rally has different (float) content: " +5240f"({l1} vs {l2}) " +5241f"({f_i1} vs {f_i2}) " +5242f"({delta:.10f}) " +5243f"({count=})")5244continue5245raise ValueError("count %u not handled" % count)5246self.progress("Rally content same")52475248def load_rally_using_mavproxy(self, filename):5249"""Load rally points from a file to flight controller."""5250self.progress("Loading rally points (%s)" % filename)5251path = os.path.join(testdir, self.current_test_name_directory, filename)5252mavproxy = self.start_mavproxy()5253mavproxy.send('rally load %s\n' % path)5254mavproxy.expect("Loaded")5255self.delay_sim_time(10) # allow transfer to complete5256self.stop_mavproxy(mavproxy)52575258def load_sample_mission(self):5259self.load_mission(self.sample_mission_filename())52605261def generic_mission_filepath_for_filename(self, filename):5262return os.path.join(testdir, "Generic_Missions", filename)52635264def load_generic_mission(self, filename, strict=True):5265return self.load_mission_from_filepath(5266self.generic_mission_filepath_for_filename(filename),5267strict=strict)52685269def load_mission(self, filename, strict=True):5270return self.load_mission_from_filepath(5271os.path.join(testdir, self.current_test_name_directory, filename),5272strict=strict)52735274def wp_to_mission_item_int(self, wp, mission_type):5275'''convert a MISSION_ITEM to a MISSION_ITEM_INT. We always send as5276MISSION_ITEM_INT to give cm level accuracy5277Swiped from mavproxy_wp.py5278'''5279if wp.get_type() == 'MISSION_ITEM_INT':5280return wp5281wp_int = mavutil.mavlink.MAVLink_mission_item_int_message(5282wp.target_system,5283wp.target_component,5284wp.seq,5285wp.frame,5286wp.command,5287wp.current,5288wp.autocontinue,5289wp.param1,5290wp.param2,5291wp.param3,5292wp.param4,5293int(wp.x*1.0e7),5294int(wp.y*1.0e7),5295wp.z,5296mission_type,5297)5298return wp_int52995300def mission_item_protocol_items_from_filepath(self,5301loaderclass,5302filepath,5303target_system=1,5304target_component=1,5305):5306'''returns a list of mission-item-ints from filepath'''5307# self.progress("filepath: %s" % filepath)5308wploader = loaderclass(5309target_system=target_system,5310target_component=target_component5311)5312itemstype = mavutil.mavlink.enums["MAV_MISSION_TYPE"][wploader.mav_mission_type()].name5313self.progress(f"Loading {itemstype} ({os.path.basename(filepath)})")5314wploader.load(filepath)5315return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:50253165317def mission_from_filepath(self, filepath, target_system=1, target_component=1):5318'''returns a list of mission-item-ints from filepath'''5319return self.mission_item_protocol_items_from_filepath(5320mavwp.MAVWPLoader,5321filepath,5322target_system=target_system,5323target_component=target_component,5324)53255326def sitl_home_string_from_mission(self, filename):5327'''return a string of the form "lat,lng,yaw,alt" from the home5328location in a mission file'''5329return "%s,%s,%s,%s" % self.get_home_tuple_from_mission(filename)53305331def sitl_home_string_from_mission_filepath(self, filepath):5332'''return a string of the form "lat,lng,yaw,alt" from the home5333location in a mission file'''5334return "%s,%s,%s,%s" % self.get_home_tuple_from_mission_filepath(filepath)53355336def get_home_tuple_from_mission(self, filename):5337'''gets item 0 from the mission file, returns a tuple suitable for5338passing to customise_SITL_commandline as --home. Yaw will be53390, so the caller may want to fill that in5340'''5341return self.get_home_tuple_from_mission_filepath(5342os.path.join(testdir, self.current_test_name_directory, filename)5343)53445345def get_home_location_from_mission(self, filename):5346(home_lat, home_lon, home_alt, heading) = self.get_home_tuple_from_mission("rover-path-planning-mission.txt")5347return mavutil.location(home_lat, home_lon)53485349def get_home_tuple_from_mission_filepath(self, filepath):5350'''gets item 0 from the mission file, returns a tuple suitable for5351passing to customise_SITL_commandline as --home. Yaw will be53520, so the caller may want to fill that in5353'''5354items = self.mission_from_filepath(filepath)5355home_item = items[0]5356return (home_item.x * 1e-7, home_item.y * 1e-7, home_item.z, 0)53575358# TODO: rename the following to "upload_mission_from_filepath"5359def load_mission_from_filepath(self,5360filepath,5361target_system=1,5362target_component=1,5363strict=True,5364reset_current_wp=True):5365wpoints_int = self.mission_from_filepath(5366filepath,5367target_system=target_system,5368target_component=target_component5369)5370self.check_mission_upload_download(wpoints_int, strict=strict)5371if reset_current_wp:5372# ArduPilot doesn't reset the current waypoint by default5373# we may be in auto mode and running waypoints, so we5374# can't check the current waypoint after resetting it.5375self.set_current_waypoint(0, check_afterwards=False)5376return len(wpoints_int)53775378def load_mission_using_mavproxy(self, mavproxy, filename):5379return self.load_mission_from_filepath_using_mavproxy(5380mavproxy,5381self.current_test_name_directory,5382filename)53835384def load_mission_from_filepath_using_mavproxy(self,5385mavproxy,5386filepath,5387filename):5388"""Load a mission from a file to flight controller."""5389self.progress("Loading mission (%s)" % filename)5390path = os.path.join(testdir, filepath, filename)5391tstart = self.get_sim_time()5392while True:5393t2 = self.get_sim_time()5394if t2 - tstart > 10:5395raise AutoTestTimeoutException("Failed to do waypoint thing")5396# the following hack is to get around MAVProxy statustext deduping:5397while time.time() - self.last_wp_load < 3:5398self.progress("Waiting for MAVProxy de-dupe timer to expire")5399self.drain_mav()5400time.sleep(0.1)5401mavproxy.send('wp load %s\n' % path)5402mavproxy.expect('Loaded ([0-9]+) waypoints from')5403load_count = mavproxy.match.group(1)5404self.last_wp_load = time.time()5405mavproxy.expect("Flight plan received")5406mavproxy.send('wp list\n')5407mavproxy.expect('Requesting ([0-9]+) waypoints')5408request_count = mavproxy.match.group(1)5409if load_count != request_count:5410self.progress("request_count=%s != load_count=%s" %5411(request_count, load_count))5412continue5413mavproxy.expect('Saved ([0-9]+) waypoints to (.+?way.txt)')5414save_count = mavproxy.match.group(1)5415if save_count != request_count:5416raise NotAchievedException("request count != load count")5417# warning: this assumes MAVProxy was started in the CWD!5418# on the autotest server we invoke autotest.py one-up from5419# the git root, like this:5420# timelimit 32000 APM/Tools/autotest/autotest.py --timeout=30000 > buildlogs/autotest-output.txt 2>&15421# that means the MAVProxy log files are not reltopdir!5422saved_filepath = mavproxy.match.group(2)5423saved_filepath = saved_filepath.rstrip()5424self.assert_mission_files_same(path, saved_filepath)5425break5426mavproxy.send('wp status\n')5427mavproxy.expect(r'Have (\d+) of (\d+)')5428status_have = mavproxy.match.group(1)5429status_want = mavproxy.match.group(2)5430if status_have != status_want:5431raise ValueError("status count mismatch")5432if status_have != save_count:5433raise ValueError("status have not equal to save count")54345435wploader = mavwp.MAVWPLoader()5436wploader.load(path)5437num_wp = wploader.count()5438if num_wp != int(status_have):5439raise ValueError("num_wp=%u != status_have=%u" %5440(num_wp, int(status_have)))5441if num_wp == 0:5442raise ValueError("No waypoints loaded?!")54435444return num_wp54455446def save_mission_to_file_using_mavproxy(self, mavproxy, filename):5447"""Save a mission to a file"""5448mavproxy.send('wp list\n')5449mavproxy.expect('Requesting [0-9]+ waypoints')5450mavproxy.send('wp save %s\n' % filename)5451mavproxy.expect('Saved ([0-9]+) waypoints')5452num_wp = int(mavproxy.match.group(1))5453self.progress("num_wp: %d" % num_wp)5454return num_wp54555456def string_for_frame(self, frame):5457return mavutil.mavlink.enums["MAV_FRAME"][frame].name54585459def frames_equivalent(self, f1, f2):5460pairs = [5461(mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,5462mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT),5463(mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,5464mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT),5465(mavutil.mavlink.MAV_FRAME_GLOBAL,5466mavutil.mavlink.MAV_FRAME_GLOBAL_INT),5467]5468for pair in pairs:5469if (f1 == pair[0] and f2 == pair[1]):5470return True5471if (f1 == pair[1] and f2 == pair[0]):5472return True5473return f1 == f254745475def check_mission_items_same(self,5476check_atts,5477want,5478got,5479epsilon=None,5480skip_first_item=False,5481strict=True):5482self.progress("Checking mission items same")5483if epsilon is None:5484epsilon = 15485if len(want) != len(got):5486raise NotAchievedException("Incorrect item count (want=%u got=%u)" % (len(want), len(got)))5487self.progress("Checking %u items" % len(want))5488for i in range(0, len(want)):5489if skip_first_item and i == 0:5490continue5491item = want[i]5492downloaded_item = got[i]54935494check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']5495# z is not preserved54965497self.progress("Comparing (%s) and (%s)" % (str(item), str(downloaded_item)))54985499for att in check_atts:5500item_val = getattr(item, att)5501downloaded_item_val = getattr(downloaded_item, att)5502if abs(item_val - downloaded_item_val) > epsilon:5503raise NotAchievedException(5504"Item %u (%s) has different %s after download want=%s got=%s (got-item=%s)" %5505(i, str(item), att, str(item_val), str(downloaded_item_val), str(downloaded_item)))5506# for waypoint items ensure z and frame are preserved:5507self.progress("Type is %u" % got[0].mission_type)5508if got[0].mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:5509item_val = getattr(item, 'frame')5510downloaded_item_val = getattr(downloaded_item, 'frame')5511# if you are thinking of adding another, "don't annoy5512# me, I know missions aren't troundtripped" non-strict5513# thing here, DON'T do it without first checking "def5514# assert_mission_files_same"; it makes the same checks5515# as will be needed here eventually.5516if ((strict or self.ardupilot_stores_frame_for_cmd(getattr(item, 'command'))) and5517not self.frames_equivalent(item_val, downloaded_item_val)):5518raise NotAchievedException("Frame not same (got=%s want=%s)" %5519(self.string_for_frame(downloaded_item_val),5520self.string_for_frame(item_val)))5521if downloaded_item.z == 0:5522delta = abs(item.z)5523else:5524delta = 1 - abs(item.z / downloaded_item.z)5525if delta > 0.01: # error should be less than 1 mm, but float precision issues in Python...5526raise NotAchievedException("Z not preserved (got=%f want=%f delta=%f%%)" %5527(downloaded_item.z, item.z, delta))55285529def check_fence_items_same(self, want, got, strict=True):5530check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']5531return self.check_mission_items_same(check_atts, want, got, strict=strict)55325533def check_mission_waypoint_items_same(self, want, got, strict=True):5534check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']5535return self.check_mission_items_same(check_atts, want, got, skip_first_item=True, strict=strict)55365537def check_mission_item_upload_download(self, items, itype, mission_type, strict=True):5538self.progress("check %s upload/download: upload %u items" %5539(itype, len(items),))5540self.upload_using_mission_protocol(mission_type, items)5541self.progress("check %s upload/download: download items" % itype)5542downloaded_items = self.download_using_mission_protocol(mission_type)5543if len(items) != len(downloaded_items):5544raise NotAchievedException("Did not download same number of items as uploaded want=%u got=%u" %5545(len(items), len(downloaded_items)))5546if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_FENCE:5547self.check_fence_items_same(items, downloaded_items, strict=strict)5548elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:5549self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)5550elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY:5551self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)5552else:5553raise NotAchievedException("Unhandled")55545555def check_fence_upload_download(self, items):5556self.check_mission_item_upload_download(5557items,5558"fence",5559mavutil.mavlink.MAV_MISSION_TYPE_FENCE)5560if self.use_map and self.mavproxy is not None:5561self.mavproxy.send('fence list\n')55625563def check_mission_upload_download(self, items, strict=True):5564self.check_mission_item_upload_download(5565items,5566"waypoints",5567mavutil.mavlink.MAV_MISSION_TYPE_MISSION,5568strict=strict)5569if self.use_map and self.mavproxy is not None:5570self.mavproxy.send('wp list\n')55715572def check_rally_upload_download(self, items):5573self.check_mission_item_upload_download(5574items,5575"rally",5576mavutil.mavlink.MAV_MISSION_TYPE_RALLY5577)5578if self.use_map and self.mavproxy is not None:5579self.mavproxy.send('rally list\n')55805581def check_dflog_message_rates(self, log_filepath, message_rates):5582reader = self.dfreader_for_path(log_filepath)55835584counts = {}5585first = None5586while True:5587m = reader.recv_match()5588if m is None:5589break5590if (m.fmt.instance_field is not None and5591getattr(m, m.fmt.instance_field) != 0):5592continue55935594t = m.get_type()5595# print("t=%s" % str(t))5596if t not in counts:5597counts[t] = 05598counts[t] += 155995600if hasattr(m, 'TimeUS'):5601if first is None:5602first = m5603last = m56045605if first is None:5606raise NotAchievedException("Did not get any messages")5607delta_time_us = last.TimeUS - first.TimeUS56085609for (t, want_rate) in message_rates.items():5610if t not in counts:5611raise NotAchievedException("Wanted %s but got none" % t)5612got_rate = float(counts[t]) / delta_time_us * 10000005613self.progress(f"Got ({counts[t]}) in ({delta_time_us}us) ({got_rate}/s)")56145615if abs(want_rate - got_rate) > 5:5616raise NotAchievedException("Not getting %s data at wanted rate want=%f got=%f" %5617(t, want_rate, got_rate))56185619def generate_rate_sample_log(self, log_bitmask=None):5620self.context_push()5621params = {5622"LOG_DISARMED": 0,5623"LOG_DARM_RATEMAX": 0,5624"LOG_FILE_RATEMAX": 0,5625}5626if log_bitmask is not None:5627params["LOG_BITMASK"] = log_bitmask56285629self.set_parameters(params)5630self.reboot_sitl()5631self.wait_ready_to_arm()5632self.set_parameter("LOG_DISARMED", 1)5633self.delay_sim_time(20)5634self.set_parameter("LOG_DISARMED", 0)5635path = self.current_onboard_log_filepath()5636self.progress("Rate sample log (%s)" % path)5637self.reboot_sitl() # ensure log is rotated5638self.context_pop()5639return path56405641def rc_defaults(self):5642return {56431: 1500,56442: 1500,56453: 1500,56464: 1500,56475: 1500,56486: 1500,56497: 1500,56508: 1500,56519: 1500,565210: 1500,565311: 1500,565412: 1500,565513: 1500,565614: 1500,565715: 1500,565816: 1500,5659}56605661def set_rc_from_map(self, _map, timeout=20, quiet=False):5662map_copy = _map.copy()5663for v in map_copy.values():5664if not isinstance(v, int):5665raise NotAchievedException("RC values must be integers")5666self.rc_queue.put(map_copy)56675668if self.rc_thread is None:5669self.rc_thread = threading.Thread(target=self.rc_thread_main, name='RC')5670if self.rc_thread is None:5671raise NotAchievedException("Could not create thread")5672self.rc_thread.start()56735674tstart = self.get_sim_time()5675while True:5676if self.get_sim_time_cached() - tstart > timeout:5677raise NotAchievedException("Failed to set RC values")5678m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=1)5679if m is None:5680continue5681bad_channels = ""5682for chan in map_copy:5683chan_pwm = getattr(m, "chan" + str(chan) + "_raw")5684if chan_pwm != map_copy[chan]:5685bad_channels += " (ch=%u want=%u got=%u)" % (chan, map_copy[chan], chan_pwm)5686break5687if len(bad_channels) == 0:5688if not quiet:5689self.progress("RC values good")5690break5691self.progress("RC values bad:%s" % bad_channels)5692if not self.rc_thread.is_alive():5693self.rc_thread = None5694raise ValueError("RC thread is dead") # FIXME: type56955696def rc_thread_main(self):5697chan16 = [1000] * 1656985699sitl_output = mavutil.mavudp("127.0.0.1:%u" % self.sitl_rcin_port(), input=False)5700buf = None57015702while True:5703if self.rc_thread_should_quit:5704break57055706# the 0.05 here means we're updating the RC values into5707# the autopilot at 20Hz - that's our 50Hz wallclock, , not5708# the autopilot's simulated 20Hz, so if speedup is 10 the5709# autopilot will see ~2Hz.5710timeout = 0.025711# ... and 2Hz is too slow when we now run at 100x speedup:5712timeout /= (self.speedup / 10.0)57135714try:5715map_copy = self.rc_queue.get(timeout=timeout)57165717# 16 packed entries:5718for i in range(1, 17):5719if i in map_copy:5720chan16[i-1] = map_copy[i]57215722except Queue.Empty:5723pass57245725buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)57265727if buf is None:5728continue57295730sitl_output.write(buf)57315732def set_rc_default(self):5733"""Setup all simulated RC control to 1500."""5734_defaults = self.rc_defaults()5735self.set_rc_from_map(_defaults)57365737def check_rc_defaults(self):5738"""Ensure all rc outputs are at defaults"""5739self.do_timesync_roundtrip()5740_defaults = self.rc_defaults()5741m = self.assert_receive_message('RC_CHANNELS', timeout=5)5742need_set = {}5743for chan in _defaults:5744default_value = _defaults[chan]5745current_value = getattr(m, "chan" + str(chan) + "_raw")5746if default_value != current_value:5747self.progress("chan=%u needs resetting is=%u want=%u" %5748(chan, current_value, default_value))5749need_set[chan] = default_value5750self.set_rc_from_map(need_set)57515752def set_rc(self, chan, pwm, timeout=20):5753"""Setup a simulated RC control to a PWM value"""5754self.set_rc_from_map({chan: pwm}, timeout=timeout)57555756def set_servo(self, chan, pwm):5757"""Replicate the functionality of MAVProxy: servo set <ch> <pwm>"""5758self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm)57595760def location_offset_ne(self, location, north, east):5761'''move location in metres. You probably wat offset_location_ne'''5762print("old: %f %f" % (location.lat, location.lng))5763(lat, lng) = mp_util.gps_offset(location.lat, location.lng, east, north)5764location.lat = lat5765location.lng = lng5766print("new: %f %f" % (location.lat, location.lng))57675768def home_relative_loc_ne(self, n, e):5769ret = self.home_position_as_mav_location()5770self.location_offset_ne(ret, n, e)5771return ret57725773def home_relative_loc_neu(self, n, e, u):5774ret = self.home_position_as_mav_location()5775self.location_offset_ne(ret, n, e)5776ret.alt += u5777return ret57785779def zero_throttle(self):5780"""Set throttle to zero."""5781if self.is_rover():5782self.set_rc(3, 1500)5783else:5784self.set_rc(3, 1000)57855786def set_output_to_max(self, chan):5787"""Set output to max with RC Radio taking into account REVERSED parameter."""5788is_reversed = self.get_parameter("RC%u_REVERSED" % chan)5789out_max = int(self.get_parameter("RC%u_MAX" % chan))5790out_min = int(self.get_parameter("RC%u_MIN" % chan))5791if is_reversed == 0:5792self.set_rc(chan, out_max)5793else:5794self.set_rc(chan, out_min)57955796def set_output_to_min(self, chan):5797"""Set output to min with RC Radio taking into account REVERSED parameter."""5798is_reversed = self.get_parameter("RC%u_REVERSED" % chan)5799out_max = int(self.get_parameter("RC%u_MAX" % chan))5800out_min = int(self.get_parameter("RC%u_MIN" % chan))5801if is_reversed == 0:5802self.set_rc(chan, out_min)5803else:5804self.set_rc(chan, out_max)58055806def set_output_to_trim(self, chan):5807"""Set output to trim with RC Radio."""5808out_trim = int(self.get_parameter("RC%u_TRIM" % chan))5809self.set_rc(chan, out_trim)58105811def get_stick_arming_channel(self):5812"""Return the Rudder channel number as set in parameter."""5813raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))58145815def get_disarm_delay(self):5816"""Return disarm delay value."""5817raise ErrorException("Disarm delay is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))58185819def arming_test_mission(self):5820"""Load arming test mission.5821This mission is used to allow to change mode to AUTO. For each vehicle5822it get an unlimited wait waypoint and the starting takeoff if needed."""5823if self.is_rover() or self.is_plane() or self.is_sub():5824return os.path.join(testdir, self.current_test_name_directory + "test_arming.txt")5825else:5826return None58275828def test_takeoff_check_mode(self, mode, user_takeoff=False, force_disarm=False):5829# stabilize check5830self.progress("Motor takeoff check in %s" % mode)5831self.change_mode(mode)5832self.zero_throttle()5833self.wait_ready_to_arm()5834self.context_push()5835self.context_collect('STATUSTEXT')5836self.arm_vehicle()5837if user_takeoff:5838self.run_cmd(5839mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,5840p7=10,5841)5842else:5843self.set_rc(3, 1700)5844# we may never see ourselves as armed in a heartbeat5845self.wait_statustext("Takeoff blocked: ESC RPM out of range", check_context=True)5846self.context_pop()5847self.zero_throttle()5848self.disarm_vehicle(force=force_disarm)5849self.wait_disarmed()58505851def set_safetyswitch_on(self, **kwargs):5852self.set_safetyswitch(1, **kwargs)58535854def set_safetyswitch_off(self, **kwargs):5855self.set_safetyswitch(0, **kwargs)58565857def set_safetyswitch(self, value, target_system=1, target_component=1):5858self.mav.mav.set_mode_send(5859target_system,5860mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,5861value)5862self.wait_sensor_state(5863mavutil.mavlink.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,5864True, not value, True,5865verbose=True,5866timeout=305867)58685869def armed(self, cached=False):5870"""Return True if vehicle is armed and safetyoff"""5871m = None5872if cached:5873m = self.mav.messages.get("HEARTBEAT", None)5874if m is None:5875m = self.wait_heartbeat()5876return (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 058775878def send_mavlink_arm_command(self):5879self.send_cmd(5880mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5881p1=1, # ARM5882)58835884def send_mavlink_disarm_command(self):5885self.send_cmd(5886mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5887p1=0, # DISARM5888)58895890def send_mavlink_run_prearms_command(self):5891self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)58925893def analog_rangefinder_parameters(self):5894return {5895"RNGFND1_TYPE": 1,5896"RNGFND1_MIN": 0,5897"RNGFND1_MAX": 40.00,5898"RNGFND1_SCALING": 12.12,5899"RNGFND1_PIN": 0,5900}59015902def set_analog_rangefinder_parameters(self):5903self.set_parameters(self.analog_rangefinder_parameters())59045905def send_debug_trap(self, timeout=6000):5906self.progress("Sending trap to autopilot")5907self.run_cmd(5908mavutil.mavlink.MAV_CMD_DEBUG_TRAP,5909p1=32451, # magic number to trap5910timeout=timeout,5911)59125913def try_arm(self, result=True, expect_msg=None, timeout=60):5914"""Send Arming command, wait for the expected result and statustext."""5915self.progress("Try arming and wait for expected result")5916self.drain_mav()5917self.run_cmd(5918mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5919p1=1, # ARM5920want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,5921timeout=timeout,5922)5923if expect_msg is not None:5924self.wait_statustext(5925expect_msg,5926timeout=timeout,5927the_function=lambda: self.send_cmd(5928mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5929p1=1, # ARM5930target_sysid=None,5931target_compid=None,5932))59335934def arm_vehicle(self, timeout=20, force=False):5935"""Arm vehicle with mavlink arm message."""5936self.progress("Arm motors with MAVLink cmd")5937p2 = 05938if force:5939p2 = 29895940try:5941self.run_cmd(5942mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5943p1=1, # ARM5944p2=p2,5945timeout=timeout,5946)5947except ValueError as e:5948# statustexts are queued; give it a second to arrive:5949self.delay_sim_time(5)5950raise e5951try:5952self.wait_armed()5953except AutoTestTimeoutException:5954raise AutoTestTimeoutException("Failed to ARM with mavlink")5955return True59565957def wait_armed(self, timeout=20):5958tstart = self.get_sim_time()5959while self.get_sim_time_cached() - tstart < timeout:5960self.wait_heartbeat(drain_mav=False)5961if self.mav.motors_armed():5962self.progress("Motors ARMED")5963return5964raise AutoTestTimeoutException("Did not become armed")59655966def disarm_vehicle(self, timeout=60, force=False):5967"""Disarm vehicle with mavlink disarm message."""5968self.progress("Disarm motors with MAVLink cmd")5969p2 = 05970if force:5971p2 = 21196 # magic force disarm value5972self.run_cmd(5973mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5974p1=0, # DISARM5975p2=p2,5976timeout=timeout,5977)5978self.wait_disarmed()59795980def disarm_vehicle_expect_fail(self):5981'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''5982self.progress("Disarm - expect to fail")5983self.run_cmd(5984mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,5985p1=0, # DISARM5986timeout=10,5987want_result=mavutil.mavlink.MAV_RESULT_FAILED,5988)5989self.progress("Disarm - forced")5990self.disarm_vehicle(force=True)59915992def wait_disarmed_default_wait_time(self):5993return 3059945995def wait_disarmed(self, timeout=None, tstart=None):5996if timeout is None:5997timeout = self.wait_disarmed_default_wait_time()5998self.progress("Waiting for DISARM")5999if tstart is None:6000tstart = self.get_sim_time()6001last_print_time = 06002while True:6003now = self.get_sim_time_cached()6004delta = now - tstart6005if delta > timeout:6006raise AutoTestTimeoutException("Failed to DISARM within %fs" %6007(timeout,))6008if now - last_print_time > 1:6009self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout))6010last_print_time = now6011msg = self.wait_heartbeat(quiet=True)6012if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:6013# still armed6014continue6015self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %6016(delta, timeout))6017return60186019def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'):6020'''wait for an attitude (degrees)'''6021if desroll is None and despitch is None:6022raise ValueError("despitch or desroll must be supplied")6023tstart = self.get_sim_time()6024while True:6025if self.get_sim_time_cached() - tstart > timeout:6026raise AutoTestTimeoutException("Failed to achieve attitude")6027m = self.assert_receive_message(message_type, timeout=60)6028roll_deg = math.degrees(m.roll)6029pitch_deg = math.degrees(m.pitch)6030self.progress("wait_att[%s]: roll=%f desroll=%s pitch=%f despitch=%s" %6031(message_type, roll_deg, desroll, pitch_deg, despitch))6032if desroll is not None and abs(roll_deg - desroll) > tolerance:6033continue6034if despitch is not None and abs(pitch_deg - despitch) > tolerance:6035continue6036return60376038def wait_attitude_quaternion(self,6039desroll=None,6040despitch=None,6041timeout=2,6042tolerance=10,6043message_type='ATTITUDE_QUATERNION'):6044'''wait for an attitude (degrees)'''6045if desroll is None and despitch is None:6046raise ValueError("despitch or desroll must be supplied")6047tstart = self.get_sim_time()6048while True:6049if self.get_sim_time_cached() - tstart > timeout:6050raise AutoTestTimeoutException("Failed to achieve (quaternion) attitude")6051m = self.poll_message(message_type, quiet=True)6052q = quaternion.Quaternion([m.q1, m.q2, m.q3, m.q4])6053euler = q.euler6054roll = euler[0]6055pitch = euler[1]6056roll_deg = math.degrees(roll)6057pitch_deg = math.degrees(pitch)6058self.progress("wait_att_quat[%s]: roll=%f desroll=%s pitch=%f despitch=%s" %6059(message_type, roll_deg, desroll, pitch_deg, despitch))6060if desroll is not None and abs(roll_deg - desroll) > tolerance:6061continue6062if despitch is not None and abs(pitch_deg - despitch) > tolerance:6063continue6064self.progress("wait_att_quat: achieved")6065return60666067def CPUFailsafe(self):6068'''Ensure we do something appropriate when the main loop stops'''6069# Most vehicles just disarm on failsafe6070# customising the SITL commandline ensures the process will6071# get stopped/started at the end of the test6072if self.frame is None:6073raise ValueError("Frame is none?")6074self.customise_SITL_commandline([])6075self.wait_ready_to_arm()6076self.arm_vehicle()6077self.progress("Sending enter-cpu-lockup")6078# when we're in CPU lockup we don't get SYSTEM_TIME messages,6079# so get_sim_time breaks:6080tstart = self.get_sim_time()6081self.send_cmd_enter_cpu_lockup()6082self.wait_disarmed(timeout=5, tstart=tstart)6083# we're not getting SYSTEM_TIME messages at this point.... and6084# we're in a weird state where the vehicle is armed but the6085# motors are not, and we can't disarm further because Copter6086# looks at whether its *motors* are armed as part of its6087# disarm process.6088self.reset_SITL_commandline()60896090def cpufailsafe_wait_servo_channel_value(self, channel, value, timeout=30):6091'''we get restricted messages while doing cpufailsafe, this working then'''6092start = time.time()6093while True:6094if time.time() - start > timeout:6095raise NotAchievedException("Did not achieve value")6096m = self.assert_receive_message('SERVO_OUTPUT_RAW')6097channel_field = "servo%u_raw" % channel6098m_value = getattr(m, channel_field, None)6099self.progress("Servo%u=%u want=%u" % (channel, m_value, value))6100if m_value == value:6101break61026103def plane_CPUFailsafe(self):6104'''In lockup Plane should copy RC inputs to RC outputs'''6105# customising the SITL commandline ensures the process will6106# get stopped/started at the end of the test6107self.customise_SITL_commandline([])6108self.wait_ready_to_arm()6109self.arm_vehicle()6110self.progress("Sending enter-cpu-lockup")6111# when we're in CPU lockup we don't get SYSTEM_TIME messages,6112# so get_sim_time breaks:6113self.send_cmd_enter_cpu_lockup()6114start_time = time.time() # not sim time!6115self.context_push()6116self.context_collect("STATUSTEXT")6117while True:6118want = "Initialising ArduPilot"6119if time.time() - start_time > 30:6120raise NotAchievedException("Did not get %s" % want)6121# we still need to parse the incoming messages:6122try:6123self.wait_statustext(want, timeout=0.1, check_context=True, wallclock_timeout=1)6124break6125except AutoTestTimeoutException:6126pass6127self.context_pop()6128# Different scaling for RC input and servo output means the6129# servo output value isn't the rc input value:6130self.progress("Setting RC to 1200")6131self.rc_queue.put({2: 1200})6132self.progress("Waiting for servo of 1260")6133self.cpufailsafe_wait_servo_channel_value(2, 1260)6134self.rc_queue.put({2: 1700})6135self.cpufailsafe_wait_servo_channel_value(2, 1660)6136self.reset_SITL_commandline()61376138def mavproxy_arm_vehicle(self, mavproxy):6139"""Arm vehicle with mavlink arm message send from MAVProxy."""6140self.progress("Arm motors with MavProxy")6141mavproxy.send('arm throttle\n')6142self.wait_armed()6143self.progress("ARMED")6144return True61456146def mavproxy_disarm_vehicle(self, mavproxy):6147"""Disarm vehicle with mavlink disarm message send from MAVProxy."""6148self.progress("Disarm motors with MavProxy")6149mavproxy.send('disarm\n')6150self.wait_disarmed()61516152def arm_motors_with_rc_input(self, timeout=20):6153"""Arm motors with radio."""6154self.progress("Arm motors with radio")6155self.set_output_to_max(self.get_stick_arming_channel())6156tstart = self.get_sim_time()6157while True:6158self.wait_heartbeat()6159tdelta = self.get_sim_time_cached() - tstart6160if self.mav.motors_armed():6161self.progress("MOTORS ARMED OK WITH RADIO")6162self.set_output_to_trim(self.get_stick_arming_channel())6163self.progress("Arm in %ss" % tdelta) # TODO check arming time6164return6165self.progress("Not armed after %f seconds" % (tdelta))6166if tdelta > timeout:6167break6168self.set_output_to_trim(self.get_stick_arming_channel())6169raise NotAchievedException("Failed to ARM with radio")61706171def disarm_motors_with_rc_input(self, timeout=20, watch_for_disabled=False):6172"""Disarm motors with radio."""6173self.progress("Disarm motors with radio")6174self.do_timesync_roundtrip()6175self.context_push()6176self.context_collect('STATUSTEXT')6177self.set_output_to_min(self.get_stick_arming_channel())6178tstart = self.get_sim_time()6179ret = False6180while self.get_sim_time_cached() < tstart + timeout:6181self.wait_heartbeat()6182if not self.mav.motors_armed():6183disarm_delay = self.get_sim_time_cached() - tstart6184self.progress("MOTORS DISARMED OK WITH RADIO (in %ss)" % disarm_delay)6185ret = True6186break6187if self.statustext_in_collections("Rudder disarm: disabled"):6188self.progress("Found 'Rudder disarm: disabled' in statustext")6189break6190self.context_clear_collection('STATUSTEXT')6191self.set_output_to_trim(self.get_stick_arming_channel())6192self.context_pop()6193if not ret:6194raise NotAchievedException("Failed to DISARM with RC input")61956196def arm_motors_with_switch(self, switch_chan, timeout=20):6197"""Arm motors with switch."""6198self.progress("Arm motors with switch %d" % switch_chan)6199self.set_rc(switch_chan, 2000)6200tstart = self.get_sim_time()6201while self.get_sim_time_cached() - tstart < timeout:6202self.wait_heartbeat()6203if self.mav.motors_armed():6204self.progress("MOTORS ARMED OK WITH SWITCH")6205return6206raise NotAchievedException("Failed to ARM with switch")62076208def disarm_motors_with_switch(self, switch_chan, timeout=20):6209"""Disarm motors with switch."""6210self.progress("Disarm motors with switch %d" % switch_chan)6211self.set_rc(switch_chan, 1000)6212tstart = self.get_sim_time()6213while self.get_sim_time_cached() < tstart + timeout:6214self.wait_heartbeat()6215if not self.mav.motors_armed():6216self.progress("MOTORS DISARMED OK WITH SWITCH")6217return6218raise NotAchievedException("Failed to DISARM with switch")62196220def disarm_wait(self, timeout=10):6221tstart = self.get_sim_time()6222while True:6223if self.get_sim_time_cached() - tstart > timeout:6224raise NotAchievedException("Did not disarm")6225self.wait_heartbeat()6226if not self.mav.motors_armed():6227return62286229def wait_autodisarm_motors(self):6230"""Wait for Autodisarm motors within disarm delay6231this feature is only available in copter (DISARM_DELAY) and plane (LAND_DISARMDELAY)."""6232self.progress("Wait autodisarming motors")6233disarm_delay = self.get_disarm_delay()6234tstart = self.get_sim_time()6235timeout = disarm_delay * 26236while self.get_sim_time_cached() < tstart + timeout:6237self.wait_heartbeat()6238if not self.mav.motors_armed():6239disarm_time = self.get_sim_time_cached() - tstart6240self.progress("MOTORS AUTODISARMED")6241self.progress("Autodisarm in %ss, expect less than %ss" % (disarm_time, disarm_delay))6242return disarm_time <= disarm_delay6243raise AutoTestTimeoutException("Failed to AUTODISARM")62446245def set_autodisarm_delay(self, delay):6246"""Set autodisarm delay"""6247raise ErrorException("Auto disarm is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))62486249@staticmethod6250def should_fetch_all_for_parameter_change(param_name):6251return False # FIXME: if we allow MAVProxy then allow this6252if fnmatch.fnmatch(param_name, "*_ENABLE") or fnmatch.fnmatch(param_name, "*_ENABLED"):6253return True6254if param_name in ["ARSPD_TYPE",6255"ARSPD2_TYPE",6256"BATT2_MONITOR",6257"CAN_DRIVER",6258"COMPASS_PMOT_EN",6259"OSD_TYPE",6260"RSSI_TYPE",6261"WENC_TYPE"]:6262return True6263return False62646265def set_parameter_bit(self, name: str, bit_offset: int) -> None:6266'''set bit in parameter to true, preserving values of other bits'''6267value = int(self.get_parameter(name))6268value |= 1 << bit_offset6269self.set_parameter(name, value)62706271def clear_parameter_bit(self, name: str, bit_offset: int) -> None:6272'''set bit in parameter to true, preserving values of other bits'''6273value = int(self.get_parameter(name))6274value &= ~(1 << bit_offset)6275self.set_parameter(name, value)62766277def send_set_parameter_direct(self, name, value):6278self.mav.mav.param_set_send(self.sysid_thismav(),62791,6280name.encode('ascii'),6281value,6282mavutil.mavlink.MAV_PARAM_TYPE_REAL32)62836284def send_set_parameter_mavproxy(self, name, value):6285self.mavproxy.send("param set %s %s\n" % (name, str(value)))62866287def send_set_parameter(self, name, value, verbose=False):6288if verbose:6289self.progress("Send set param for (%s) (%f)" % (name, value))6290return self.send_set_parameter_direct(name, value)62916292def set_parameter(self, name, value, **kwargs):6293self.set_parameters({name: value}, **kwargs)62946295def set_parameters(self, parameters, add_to_context=True, epsilon_pct=0.00001, verbose=True, attempts=None):6296"""Set parameters from vehicle."""62976298want = copy.copy(parameters)6299self.progress("set_parameters: (%s)" % str(want))6300self.drain_mav()6301if len(want) == 0:6302return63036304if attempts is None:6305# we can easily fill ArduPilot's param-set/param-get queue6306# which is quite short. So we retry *a lot*.6307attempts = len(want) * 1063086309param_value_messages = []63106311def add_param_value(mav, m):6312t = m.get_type()6313if t != "PARAM_VALUE":6314return6315param_value_messages.append(m)63166317self.install_message_hook(add_param_value)63186319original_values = {}6320autopilot_values = {}6321for i in range(attempts):6322self.drain_mav(quiet=True)6323self.drain_all_pexpects()6324received = set()6325for (name, value) in want.items():6326if verbose:6327self.progress("%s want=%f autopilot=%s (attempt=%u/%u)" %6328(name, value, autopilot_values.get(name, 'None'), i+1, attempts))6329if name not in autopilot_values:6330if verbose:6331self.progress("Requesting (%s)" % (name,))6332self.send_get_parameter_direct(name)6333continue6334delta = abs(autopilot_values[name] - value)6335if delta <= epsilon_pct*0.01*abs(value):6336# correct value6337self.progress("%s is now %f" % (name, autopilot_values[name]))6338if add_to_context:6339context_param_name_list = [p[0] for p in self.context_get().parameters]6340if name.upper() not in context_param_name_list:6341self.context_get().parameters.append((name, original_values[name]))6342received.add(name)6343continue6344self.progress("Sending set (%s) to (%f) (old=%f)" % (name, value, original_values[name]))6345self.send_set_parameter_direct(name, value)6346for name in received:6347del want[name]6348if len(want):6349# problem here is that a reboot can happen after we6350# send the request but before we receive the reply:6351try:6352self.do_timesync_roundtrip(quiet=True)6353except AutoTestTimeoutException:6354pass6355for m in param_value_messages:6356if m.param_id in want:6357self.progress("Received wanted PARAM_VALUE %s=%f" %6358(str(m.param_id), m.param_value))6359autopilot_values[m.param_id] = m.param_value6360if m.param_id not in original_values:6361original_values[m.param_id] = m.param_value6362param_value_messages = []63636364self.remove_message_hook(add_param_value)63656366if len(want) == 0:6367return6368raise ValueError("Failed to set parameters (%s)" % want)63696370def reorder_compass_appearance(self, device_ids):6371"""6372Set compass appearance order by mapping device IDs to SIM_MAGx_DEVID parameters.63736374Args:6375device_ids: List of device IDs in desired order63766377Example:6378# Swap compass 2 and compass 46379original_ids = self.get_sim_mag_devids(6)6380# Reorder: [dev1, dev4, dev3, dev2, dev5, dev6]6381reordered = [original_ids[0], original_ids[3], original_ids[2],6382original_ids[1], original_ids[4], original_ids[5]]6383self.reorder_compass_appearance(reordered)6384"""6385# Build parameter dictionary6386params = {}6387for i, dev_id in enumerate(device_ids):6388param_name = f"SIM_MAG{i + 1}_DEVID"6389params[param_name] = dev_id63906391# Apply the parameters6392self.set_parameters(params)63936394def check_mag_devids_detected(self, num_compasses):6395"""6396Check if all SIM_MAGx_DEVID values are present in COMPASS_DEV_ID parameters.63976398Args:6399num_compasses: Number of compasses to check64006401Raises:6402NotAchievedException: If any SIM_MAG device ID is not found in COMPASS_DEV_ID slots6403"""6404# Fetch SIM_MAGx_DEVID values6405sim_device_ids = self.get_sim_mag_devids(num_compasses)64066407# Fetch COMPASS_DEV_ID values6408compass_dev_ids = []6409for i in range(1, num_compasses + 1):6410suffix = "" if i == 1 else str(i)6411dev_id = self.get_parameter(f"COMPASS_DEV_ID{suffix}")6412self.progress(f"COMPASS_DEV_ID{suffix} = {dev_id}")6413compass_dev_ids.append(dev_id)64146415# Check that each SIM_MAG device ID is present in COMPASS_DEV_ID6416for sim_id in sim_device_ids:6417if sim_id not in compass_dev_ids:6418raise NotAchievedException(6419f"SIM_MAG device ID {sim_id} not found in COMPASS_DEV_ID slots. "6420f"SIM IDs: {sim_device_ids}, COMPASS IDs: {compass_dev_ids}"6421)64226423self.progress(f"All {num_compasses} compass device IDs detected")64246425def get_sim_mag_devids(self, num_compasses):6426"""6427Fetch list of device IDs from SIM_MAGx_DEVID parameters.64286429Args:6430num_compasses: Number of compasses to fetch64316432Returns:6433List of device IDs from SIM_MAG1_DEVID through SIM_MAGn_DEVID6434"""6435device_ids = []6436for i in range(1, num_compasses + 1):6437dev_id = self.get_parameter(f"SIM_MAG{i}_DEVID")6438device_ids.append(dev_id)6439self.progress(f"SIM_MAG{i}_DEVID = {dev_id}")6440return device_ids64416442# FIXME: modify assert_parameter_value to take epsilon_pct instead:6443def assert_parameter_value_pct(self, name, expected_value, max_error_percent):6444value = self.get_parameter_direct(name, verbose=False)64456446# Convert to ratio and find limits6447error_ratio = max_error_percent / 1006448limits = [expected_value * (1 + error_ratio), expected_value * (1 - error_ratio)]64496450# Ensure that min and max are always the correct way round6451upper_limit = max(limits)6452lower_limit = min(limits)64536454# Work out the true error percentage6455error_percent = math.nan6456if expected_value != 0:6457error_percent = abs(1.0 - (value / expected_value)) * 10064586459# Check value is within limits6460if (value > upper_limit) or (value < lower_limit):6461raise ValueError("%s expected %f +/- %f%% (%f to %f) got %s with %f%% error" % (6462name,6463expected_value,6464max_error_percent,6465lower_limit,6466upper_limit,6467value,6468error_percent))64696470self.progress("%s: (%f) check passed %f%% error less than %f%%" % (name, value, error_percent, max_error_percent))64716472def fetch_all_parameters(self):6473self.mav.mav.param_request_list_send(self.sysid_thismav(), 1)6474tstart = self.get_sim_time_cached()6475ret = {}6476param_count = 06477while True:6478if param_count > 100 and len(ret) == param_count:6479break6480if self.get_sim_time_cached() - tstart > 5:6481raise NotAchievedException("Did not get all params")6482m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)6483if m is None:6484continue6485if param_count is None or m.param_count > param_count:6486param_count = m.param_count6487ret[m.param_id] = m.param_value64886489return ret64906491def get_parameter(self, *args, **kwargs):6492return self.get_parameter_direct(*args, **kwargs)64936494def send_get_parameter_direct(self, name):6495encname = name6496if not isinstance(encname, bytes):6497encname = bytes(encname, 'ascii')6498self.mav.mav.param_request_read_send(self.sysid_thismav(),64991,6500encname,6501-1)65026503def get_parameter_direct(self, name, attempts=1, timeout=60, verbose=True, timeout_in_wallclock=False):6504while attempts > 0:6505attempts -= 16506if verbose:6507self.progress("Sending param_request_read for (%s)" % name)6508# we MUST parse here or collections fail where we need6509# them to work!6510self.drain_mav(quiet=True)6511if timeout_in_wallclock:6512tstart = time.time()6513else:6514tstart = self.get_sim_time()6515self.send_get_parameter_direct(name)6516while True:6517if timeout_in_wallclock:6518now = time.time()6519else:6520now = self.get_sim_time_cached()6521if tstart > now:6522self.progress("Time wrap detected")6523# we're going to have to send another request...6524break6525delta_time = now - tstart6526if delta_time > timeout:6527break6528m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)6529if verbose:6530self.progress("get_parameter(%s): %s" % (name, str(m), ))6531if m is None:6532continue6533if m.param_id == name:6534if delta_time > 5:6535self.progress("Long time to get parameter: %fs" % (delta_time,))6536return m.param_value6537if verbose:6538self.progress("(%s) != (%s)" % (m.param_id, name,))6539raise NotAchievedException("Failed to retrieve parameter (%s)" % name)65406541def get_parameter_mavproxy(self, mavproxy, name, attempts=1, timeout=60):6542"""Get parameters from vehicle."""6543for i in range(0, attempts):6544mavproxy.send("param fetch %s\n" % name)6545try:6546mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/attempts)6547try:6548# sometimes race conditions garble the MAVProxy output6549ret = float(mavproxy.match.group(1))6550except ValueError:6551continue6552return ret6553except pexpect.TIMEOUT:6554pass6555raise NotAchievedException("Failed to retrieve parameter (%s)" % name)65566557def get_parameters(self, some_list, **kwargs):6558ret = {}65596560for n in some_list:6561ret[n] = self.get_parameter(n, **kwargs)65626563return ret65646565def context_get(self):6566"""Get Saved parameters."""6567return self.contexts[-1]65686569def context_push(self):6570"""Save a copy of the parameters."""6571context = Context()6572self.contexts.append(context)6573# add a message hook so we can collect messages conveniently:65746575def mh(mav, m):6576t = m.get_type()6577if t in context.collections:6578context.collections[t].append(m)6579self.install_message_hook_context(mh)65806581def context_collect(self, msg_type):6582'''start collecting messages of type msg_type into context collection'''6583context = self.context_get()6584if msg_type in context.collections:6585return6586context.collections[msg_type] = []65876588def context_collection(self, msg_type):6589'''return messages in collection'''6590context = self.context_get()6591if msg_type not in context.collections:6592raise NotAchievedException("Not collecting (%s)" % str(msg_type))6593return context.collections[msg_type]65946595def context_clear_collection(self, msg_type):6596'''clear collection of message type msg_type'''6597context = self.context_get()6598if msg_type not in context.collections:6599raise NotAchievedException("Not collecting (%s)" % str(msg_type))6600context.collections[msg_type] = []66016602def context_stop_collecting(self, msg_type):6603'''stop collecting messages of type msg_type in context collection. Returns the collected messages'''6604context = self.context_get()6605if msg_type not in context.collections:6606raise Exception("Not collecting %s" % str(msg_type))6607ret = context.collections[msg_type]6608del context.collections[msg_type]6609return ret66106611def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False):6612"""Set parameters to origin values in reverse order."""6613dead = self.contexts.pop()6614# remove hooks first; these hooks can raise exceptions which6615# we really don't want...6616if not hooks_already_removed:6617for hook in dead.message_hooks:6618self.remove_message_hook(hook)6619for script in dead.installed_scripts:6620self.remove_installed_script(script)6621for (message_id, rate_hz) in dead.overridden_message_rates.items():6622self.set_message_rate_hz(message_id, rate_hz)6623for module in dead.installed_modules:6624print("Removing module (%s)" % module)6625self.remove_installed_modules(module)6626if dead.sitl_commandline_customised and len(self.contexts):6627self.contexts[-1].sitl_commandline_customised = True6628if dead.raising_debug_trap_on_exceptions:6629sys.settrace(None)66306631dead_parameters_dict = {}6632for p in dead.parameters:6633dead_parameters_dict[p[0]] = p[1]6634if process_interaction_allowed:6635self.set_parameters(dead_parameters_dict, add_to_context=False)66366637if getattr(self, "old_binary", None) is not None:6638self.stop_SITL()6639with open(self.binary, "wb") as f:6640f.write(self.old_binary)6641f.close()6642self.start_SITL(wipe=False)6643self.set_streamrate(self.sitl_streamrate())6644elif dead.reboot_sitl_was_done:6645self.progress("Doing implicit context-pop reboot")6646self.reboot_sitl(mark_context=False)66476648# the following method is broken under Python2; can't **build_opts6649# def context_start_custom_binary(self, extra_defines={}):6650# # grab copy of current binary:6651# context = self.context_get()6652# if getattr(context, "old_binary", None) is not None:6653# raise ValueError("Not nestable at the moment")6654# with open(self.binary, "rb") as f:6655# self.old_binary = f.read()6656# f.close()6657# build_opts = copy.copy(self.build_opts)6658# build_opts["extra_defines"] = extra_defines6659# util.build_SITL(6660# 'bin/arducopter', # FIXME!6661# **build_opts,6662# )6663# self.stop_SITL()6664# self.start_SITL(wipe=False)6665# self.set_streamrate(self.sitl_streamrate())66666667class Context(object):6668def __init__(self, testsuite):6669self.testsuite = testsuite66706671def __enter__(self):6672self.testsuite.context_push()66736674def __exit__(self, type, value, traceback):6675self.testsuite.context_pop()6676return False # re-raise any exception66776678def sysid_thismav(self):6679return 166806681def create_MISSION_ITEM_INT(6682self,6683t,6684p1=0,6685p2=0,6686p3=0,6687p4=0,6688x=0,6689y=0,6690z=0,6691frame=mavutil.mavlink.MAV_FRAME_GLOBAL,6692autocontinue=0,6693current=0,6694target_system=1,6695target_component=1,6696seq=0,6697mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION,6698):6699return self.mav.mav.mission_item_int_encode(6700target_system,6701target_component,6702seq, # seq6703frame,6704t,6705current, # current6706autocontinue, # autocontinue6707p1, # p16708p2, # p26709p3, # p36710p4, # p46711x, # latitude6712y, # longitude6713z, # altitude6714mission_type6715)67166717def run_cmd_int(self,6718command,6719p1=0,6720p2=0,6721p3=0,6722p4=0,6723x=0,6724y=0,6725z=0,6726want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,6727timeout=10,6728target_sysid=None,6729target_compid=None,6730frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,6731p5=None,6732p6=None,6733p7=None,6734quiet=False,6735mav=None,6736):67376738if mav is None:6739mav = self.mav67406741if p5 is not None:6742x = p56743if p6 is not None:6744y = p66745if p7 is not None:6746z = p767476748if target_sysid is None:6749target_sysid = self.sysid_thismav()6750if target_compid is None:6751target_compid = 167526753self.get_sim_time() # required for timeout in run_cmd_get_ack to work67546755"""Send a MAVLink command int."""6756if not quiet:6757try:6758command_name = mavutil.mavlink.enums["MAV_CMD"][command].name6759except KeyError:6760command_name = "UNKNOWNu"6761self.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)" % (6762target_sysid,6763target_compid,6764command_name,6765command,6766p1,6767p2,6768p3,6769p4,6770x,6771y,6772z,6773frame6774))6775mav.mav.command_int_send(target_sysid,6776target_compid,6777frame,6778command,67790, # current67800, # autocontinue6781p1,6782p2,6783p3,6784p4,6785x,6786y,6787z)6788self.run_cmd_get_ack(command, want_result, timeout, mav=mav)67896790def send_cmd(self,6791command,6792p1=0,6793p2=0,6794p3=0,6795p4=0,6796p5=0,6797p6=0,6798p7=0,6799target_sysid=None,6800target_compid=None,6801mav=None,6802quiet=False,6803):6804"""Send a MAVLink command long."""6805if mav is None:6806mav = self.mav6807if target_sysid is None:6808target_sysid = self.sysid_thismav()6809if target_compid is None:6810target_compid = 16811if not quiet:6812try:6813command_name = mavutil.mavlink.enums["MAV_CMD"][command].name6814except KeyError:6815command_name = "UNKNOWN"6816self.progress("Sending COMMAND_LONG to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" %6817(6818target_sysid,6819target_compid,6820command_name,6821command,6822p1,6823p2,6824p3,6825p4,6826p5,6827p6,6828p7))6829mav.mav.command_long_send(target_sysid,6830target_compid,6831command,68321, # confirmation6833p1,6834p2,6835p3,6836p4,6837p5,6838p6,6839p7)68406841def run_cmd(self,6842command,6843p1=0,6844p2=0,6845p3=0,6846p4=0,6847p5=0,6848p6=0,6849p7=0,6850want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,6851target_sysid=None,6852target_compid=None,6853timeout=10,6854quiet=False,6855mav=None):6856self.drain_mav(mav=mav)6857self.get_sim_time() # required for timeout in run_cmd_get_ack to work6858self.send_cmd(6859command,6860p1,6861p2,6862p3,6863p4,6864p5,6865p6,6866p7,6867target_sysid=target_sysid,6868target_compid=target_compid,6869mav=mav,6870quiet=quiet,6871)6872self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet, mav=mav)68736874def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, ignore_in_progress=None):6875# note that the caller should ensure that this cached6876# timestamp is reasonably up-to-date!6877if mav is None:6878mav = self.mav6879if ignore_in_progress is None:6880ignore_in_progress = want_result != mavutil.mavlink.MAV_RESULT_IN_PROGRESS6881tstart = self.get_sim_time_cached()6882while True:6883if mav != self.mav:6884self.drain_mav()6885delta_time = self.get_sim_time_cached() - tstart6886if delta_time > timeout:6887raise AutoTestTimeoutException("Did not get good COMMAND_ACK within %fs" % timeout)6888m = mav.recv_match(type='COMMAND_ACK',6889blocking=True,6890timeout=0.1)6891if m is None:6892continue6893if not quiet:6894self.progress("ACK received: %s (%fs)" % (str(m), delta_time))6895if m.command == command:6896if m.result == mavutil.mavlink.MAV_RESULT_IN_PROGRESS and ignore_in_progress:6897continue6898if m.result != want_result:6899raise ValueError("Expected %s got %s" % (6900mavutil.mavlink.enums["MAV_RESULT"][want_result].name,6901mavutil.mavlink.enums["MAV_RESULT"][m.result].name))6902break69036904def set_current_waypoint_using_mav_cmd_do_set_mission_current(6905self,6906seq,6907reset=0,6908target_sysid=1,6909target_compid=1):6910self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,6911p1=seq,6912p2=reset,6913timeout=1,6914target_sysid=target_sysid,6915target_compid=target_compid)69166917def set_current_waypoint_using_mission_set_current(6918self,6919seq,6920target_sysid=1,6921target_compid=1,6922check_afterwards=True):6923self.mav.mav.mission_set_current_send(target_sysid,6924target_compid,6925seq)6926if check_afterwards:6927self.wait_current_waypoint(seq, timeout=10)69286929def set_current_waypoint(self, seq, target_sysid=1, target_compid=1, check_afterwards=True):6930return self.set_current_waypoint_using_mission_set_current(6931seq,6932target_sysid,6933target_compid,6934check_afterwards=check_afterwards6935)69366937def verify_parameter_values(self, parameter_stuff, max_delta=0.0):6938bad = ""6939for param in parameter_stuff:6940fetched_value = self.get_parameter(param)6941wanted_value = parameter_stuff[param]6942if isinstance(wanted_value, tuple):6943max_delta = wanted_value[1]6944wanted_value = wanted_value[0]6945if abs(fetched_value - wanted_value) > max_delta:6946bad += "%s=%f (want=%f +/-%f) " % (param, fetched_value, wanted_value, max_delta)6947if len(bad):6948raise NotAchievedException("Bad parameter values: %s" %6949(bad,))69506951#################################################6952# UTILITIES6953#################################################6954def lineno(self):6955'''return line number'''6956frameinfo = getframeinfo(currentframe().f_back)6957# print(frameinfo.filename, frameinfo.lineno)6958return frameinfo.lineno69596960@staticmethod6961def longitude_scale(lat):6962ret = math.cos(lat * (math.radians(1)))6963print("scale=%f" % ret)6964return ret69656966@staticmethod6967def get_distance(loc1, loc2):6968"""Get ground distance between two locations."""6969return TestSuite.get_distance_accurate(loc1, loc2)6970# dlat = loc2.lat - loc1.lat6971# try:6972# dlong = loc2.lng - loc1.lng6973# except AttributeError:6974# dlong = loc2.lon - loc1.lon69756976# return math.sqrt((dlat*dlat) + (dlong*dlong)*TestSuite.longitude_scale(loc2.lat)) * 1.113195e569776978@staticmethod6979def get_distance_accurate(loc1, loc2):6980"""Get ground distance between two locations."""6981try:6982lon1 = loc1.lng6983lon2 = loc2.lng6984except AttributeError:6985lon1 = loc1.lon6986lon2 = loc2.lon69876988return mp_util.gps_distance(loc1.lat, lon1, loc2.lat, lon2)69896990def assert_distance(self, loc1, loc2, min_distance, max_distance):6991dist = self.get_distance_accurate(loc1, loc2)6992if dist < min_distance or dist > max_distance:6993raise NotAchievedException("Expected distance %f to be between %f and %f" %6994(dist, min_distance, max_distance))6995self.progress("Distance %f is between %f and %f" %6996(dist, min_distance, max_distance))69976998@staticmethod6999def get_latlon_attr(loc, attrs):7000'''return any found latitude attribute from loc'''7001ret = None7002for attr in attrs:7003if hasattr(loc, attr):7004ret = getattr(loc, attr)7005break7006if ret is None:7007raise ValueError("None of %s in loc(%s)" % (str(attrs), str(loc)))7008return ret70097010@staticmethod7011def get_lat_attr(loc):7012'''return any found latitude attribute from loc'''7013return TestSuite.get_latlon_attr(loc, ["lat", "latitude"])70147015@staticmethod7016def get_lon_attr(loc):7017'''return any found latitude attribute from loc'''7018return TestSuite.get_latlon_attr(loc, ["lng", "lon", "longitude"])70197020@staticmethod7021def get_distance_int(loc1, loc2):7022"""Get ground distance between two locations in the normal "int" form7023- lat/lon multiplied by 1e7"""7024loc1_lat = TestSuite.get_lat_attr(loc1)7025loc2_lat = TestSuite.get_lat_attr(loc2)7026loc1_lon = TestSuite.get_lon_attr(loc1)7027loc2_lon = TestSuite.get_lon_attr(loc2)70287029return TestSuite.get_distance_accurate(7030mavutil.location(loc1_lat*1e-7, loc1_lon*1e-7),7031mavutil.location(loc2_lat*1e-7, loc2_lon*1e-7))70327033# dlat = loc2_lat - loc1_lat7034# dlong = loc2_lon - loc1_lon7035#7036# dlat /= 10000000.07037# dlong /= 10000000.07038#7039# return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e570407041def bearing_to(self, loc):7042'''return bearing from here to location'''7043here = self.mav.location()7044return self.get_bearing(here, loc)70457046@staticmethod7047def get_bearing(loc1, loc2):7048"""Get bearing from loc1 to loc2."""7049off_x = loc2.lng - loc1.lng7050off_y = loc2.lat - loc1.lat7051bearing = 90.00 + math.atan2(-off_y, off_x) * 57.29577957052if bearing < 0:7053bearing += 360.007054return bearing70557056def send_cmd_do_set_mode(self, mode):7057self.send_cmd(7058mavutil.mavlink.MAV_CMD_DO_SET_MODE,7059p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,7060p2=self.get_mode_from_mode_mapping(mode),7061)70627063def assert_mode(self, mode):7064self.wait_mode(mode, timeout=0)70657066def change_mode(self, mode, timeout=60):7067'''change vehicle flightmode'''7068self.wait_heartbeat()7069self.progress("Changing mode to %s" % mode)7070self.send_cmd_do_set_mode(mode)7071tstart = self.get_sim_time()7072while not self.mode_is(mode):7073custom_num = self.mav.messages['HEARTBEAT'].custom_mode7074self.progress("mav.flightmode=%s Want=%s custom=%u" % (7075self.mav.flightmode, mode, custom_num))7076if (timeout is not None and7077self.get_sim_time_cached() > tstart + timeout):7078raise WaitModeTimeout("Did not change mode")7079self.send_cmd_do_set_mode(mode)7080self.progress("Got mode %s" % mode)70817082def capable(self, capability):7083return self.get_autopilot_capabilities() & capability70847085def assert_capability(self, capability):7086if not self.capable(capability):7087name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name7088raise NotAchievedException("AutoPilot does not have capbility %s" % (name,))70897090def assert_no_capability(self, capability):7091if self.capable(capability):7092name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name7093raise NotAchievedException("AutoPilot has feature %s (when it shouldn't)" % (name,))70947095def get_autopilot_capabilities(self):7096self.context_push()7097self.context_collect('AUTOPILOT_VERSION')7098self.run_cmd(7099mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,7100p1=1, # 1: Request autopilot version7101)7102m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10, check_context=True)7103self.context_pop()7104return m.capabilities71057106def decode_flight_sw_version(self, flight_sw_version: int):7107""" Decode 32 bit flight_sw_version mavlink parameter7108corresponds to encoding in ardupilot GCS_MAVLINK::send_autopilot_version."""7109fw_type_id = (flight_sw_version >> 0) % 2567110patch = (flight_sw_version >> 8) % 2567111minor = (flight_sw_version >> 16) % 2567112major = (flight_sw_version >> 24) % 2567113if fw_type_id == 0:7114fw_type = "dev"7115elif fw_type_id == 64:7116fw_type = "alpha"7117elif fw_type_id == 128:7118fw_type = "beta"7119elif fw_type_id == 192:7120fw_type = "rc"7121elif fw_type_id == 255:7122fw_type = "official"7123else:7124fw_type = "undefined"7125return major, minor, patch, fw_type71267127def get_autopilot_firmware_version(self):7128self.mav.mav.command_long_send(self.sysid_thismav(),71291,7130mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,71310, # confirmation71321, # 1: Request autopilot version71330,71340,71350,71360,71370,71380)7139m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)7140self.fcu_firmware_version = self.decode_flight_sw_version(m.flight_sw_version)71417142def hex_values_to_int(hex_values):7143# Convert ascii codes to characters7144hex_chars = [chr(int(hex_value)) for hex_value in hex_values]7145# Convert hex characters to integers, handle \x00 case7146int_values = [0 if hex_char == '\x00' else int(hex_char, 16) for hex_char in hex_chars]7147return int_values71487149fcu_hash_to_hex = ""7150for i in hex_values_to_int(m.flight_custom_version):7151fcu_hash_to_hex += f"{i:x}"7152self.fcu_firmware_hash = fcu_hash_to_hex7153self.progress(f"Firmware Version {self.fcu_firmware_version}")7154self.progress(f"Firmware hash {self.fcu_firmware_hash}")7155self.githash = util.get_git_hash(short=True)7156self.progress(f"Git hash {self.githash}")71577158def GetCapabilities(self):7159'''Get Capabilities'''7160self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT)7161self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION)71627163def get_mode_from_mode_mapping(self, mode) -> int:7164"""Validate and return the mode number from a string or int."""7165if isinstance(mode, int):7166return mode7167mode_map = self.mav.mode_mapping()7168if mode_map is None:7169mav_type = self.mav.messages['HEARTBEAT'].type7170mav_autopilot = self.mav.messages['HEARTBEAT'].autopilot7171raise ErrorException("No mode map for (mav_type=%s mav_autopilot=%s)" % (mav_type, mav_autopilot))7172if isinstance(mode, str):7173if mode in mode_map:7174return mode_map.get(mode)7175if mode in mode_map.values():7176return mode7177self.progress("No mode (%s); available modes '%s'" % (mode, mode_map))7178raise ErrorException("Unknown mode '%s'" % mode)71797180def get_mode_string_for_mode(self, mode):7181if isinstance(mode, str):7182return mode7183mode_map = self.mav.mode_mapping()7184if mode_map is None:7185return f"mode={mode}"7186for (n, v) in mode_map.items():7187if v == mode:7188return n7189self.progress(f"No mode ({mode} {type(mode)}); available modes '{mode_map}'")7190raise ErrorException("Unknown mode '%s'" % mode)71917192def run_cmd_do_set_mode(self,7193mode,7194timeout=30,7195run_cmd=None,7196want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7197if run_cmd is None:7198run_cmd = self.run_cmd7199base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED7200custom_mode = self.get_mode_from_mode_mapping(mode)7201run_cmd(7202mavutil.mavlink.MAV_CMD_DO_SET_MODE,7203p1=base_mode,7204p2=custom_mode,7205want_result=want_result,7206timeout=timeout,7207)72087209def do_set_mode_via_command_XYZZY(self, mode, run_cmd, timeout=30):7210"""Set mode with a command long message."""7211tstart = self.get_sim_time()7212want_custom_mode = self.get_mode_from_mode_mapping(mode)7213while True:7214remaining = timeout - (self.get_sim_time_cached() - tstart)7215if remaining <= 0:7216raise AutoTestTimeoutException("Failed to change mode")7217self.run_cmd_do_set_mode(mode, run_cmd=run_cmd, timeout=10)7218m = self.wait_heartbeat()7219self.progress("Got mode=%u want=%u" % (m.custom_mode, want_custom_mode))7220if m.custom_mode == want_custom_mode:7221return72227223def do_set_mode_via_command_long(self, mode, timeout=30):7224self.do_set_mode_via_command_XYZZY(mode, self.run_cmd, timeout=timeout)72257226def do_set_mode_via_command_int(self, mode, timeout=30):7227self.do_set_mode_via_command_XYZZY(mode, self.run_cmd_int, timeout=timeout)72287229def mavproxy_do_set_mode_via_command_long(self, mavproxy, mode, timeout=30):7230"""Set mode with a command long message with Mavproxy."""7231base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED7232custom_mode = self.get_mode_from_mode_mapping(mode)7233tstart = self.get_sim_time()7234while True:7235remaining = timeout - (self.get_sim_time_cached() - tstart)7236if remaining <= 0:7237raise AutoTestTimeoutException("Failed to change mode")7238mavproxy.send("long DO_SET_MODE %u %u\n" %7239(base_mode, custom_mode))7240m = self.wait_heartbeat()7241if m.custom_mode == custom_mode:7242return True72437244def reach_heading_manual(self, heading, turn_right=True):7245"""Manually direct the vehicle to the target heading."""7246if self.is_copter() or self.is_sub():7247self.set_rc(4, 1580)7248self.wait_heading(heading)7249self.set_rc(4, 1500)7250if self.is_plane():7251self.set_rc(1, 1800)7252self.wait_heading(heading)7253self.set_rc(1, 1500)7254if self.is_rover():7255steering_pwm = 17007256if not turn_right:7257steering_pwm = 13007258self.set_rc(1, steering_pwm)7259self.set_rc(3, 1550)7260self.wait_heading(heading)7261self.set_rc(3, 1500)7262self.set_rc(1, 1500)72637264def assert_vehicle_location_is_at_startup_location(self, dist_max=1):7265here = self.mav.location()7266start_loc = self.sitl_start_location()7267dist = self.get_distance(here, start_loc)7268data = "dist=%f max=%f (here: %s start-loc: %s)" % (dist, dist_max, here, start_loc)72697270if dist > dist_max:7271raise NotAchievedException("Far from startup location: %s" % data)7272self.progress("Close to startup location: %s" % data)72737274def assert_simstate_location_is_at_startup_location(self, dist_max=1):7275simstate_loc = self.sim_location()7276start_loc = self.sitl_start_location()7277dist = self.get_distance(simstate_loc, start_loc)7278data = "dist=%f max=%f (simstate: %s start-loc: %s)" % (dist, dist_max, simstate_loc, start_loc)72797280if dist > dist_max:7281raise NotAchievedException("simstate far from startup location: %s" % data)7282self.progress("Simstate Close to startup location: %s" % data)72837284def reach_distance_manual(self, distance):7285"""Manually direct the vehicle to the target distance from home."""7286if self.is_copter():7287self.set_rc(2, 1350)7288self.wait_distance(distance, accuracy=5, timeout=60)7289self.set_rc(2, 1500)7290if self.is_plane():7291self.progress("NOT IMPLEMENTED")7292if self.is_rover():7293self.set_rc(3, 1700)7294self.wait_distance(distance, accuracy=2)7295self.set_rc(3, 1500)72967297def guided_achieve_heading(self, heading, accuracy=None):7298tstart = self.get_sim_time()7299self.run_cmd(7300mavutil.mavlink.MAV_CMD_CONDITION_YAW,7301p1=heading, # target angle7302p2=10, # degrees/second7303p3=1, # -1 is counter-clockwise, 1 clockwise7304p4=0, # 1 for relative, 0 for absolute7305)7306while True:7307if self.get_sim_time_cached() - tstart > 200:7308raise NotAchievedException("Did not achieve heading")7309m = self.assert_receive_message('VFR_HUD')7310self.progress("heading=%d want=%d" % (m.heading, int(heading)))7311if accuracy is not None:7312delta = abs(m.heading - int(heading))7313if delta <= accuracy:7314return7315if m.heading == int(heading):7316return73177318def assert_heading(self, heading, accuracy=1):7319'''assert vehicle yaw is to heading (0-360)'''7320m = self.assert_receive_message('VFR_HUD')7321if self.heading_delta(heading, m.heading) > accuracy:7322raise NotAchievedException("Unexpected heading=%f want=%f" %7323(m.heading, heading))73247325def do_set_relay(self, relay_num, on_off, timeout=10):7326"""Set relay with a command long message."""7327self.progress("Set relay %d to %d" % (relay_num, on_off))7328self.run_cmd(7329mavutil.mavlink.MAV_CMD_DO_SET_RELAY,7330p1=relay_num,7331p2=on_off,7332timeout=timeout,7333)73347335def do_set_relay_mavproxy(self, relay_num, on_off):7336"""Set relay with mavproxy."""7337self.progress("Set relay %d to %d" % (relay_num, on_off))7338self.mavproxy.send('module load relay\n')7339self.mavproxy.expect("Loaded module relay")7340self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off))73417342def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7343self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result)73447345def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7346self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result)73477348def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7349self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result)73507351def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):7352self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result)73537354#################################################7355# WAIT UTILITIES7356#################################################7357def delay_sim_time(self, seconds_to_wait, reason=None):7358"""Wait some second in SITL time."""7359tstart = self.get_sim_time()7360tnow = tstart7361r = "Delaying %f seconds"7362if reason is not None:7363r += " for %s" % reason7364self.progress(r % (seconds_to_wait,))7365while tstart + seconds_to_wait > tnow:7366tnow = self.get_sim_time(drain_mav=False)73677368def send_terrain_check_message(self):7369here = self.mav.location()7370self.mav.mav.terrain_check_send(int(here.lat * 1e7), int(here.lng * 1e7))73717372def get_terrain_height(self, verbose=False):7373self.send_terrain_check_message()7374m = self.assert_receive_message('TERRAIN_REPORT', very_verbose=True)7375return m.terrain_height73767377def get_altitude(self, relative=False, timeout=30, altitude_source=None):7378'''returns vehicles altitude in metres, possibly relative-to-home'''7379if altitude_source is None:7380if relative:7381altitude_source = "GLOBAL_POSITION_INT.relative_alt"7382else:7383altitude_source = "GLOBAL_POSITION_INT.alt"7384if altitude_source == "TERRAIN_REPORT.current_height":7385terrain = self.assert_receive_message('TERRAIN_REPORT')7386return terrain.current_height73877388(msg, field) = altitude_source.split('.')7389msg = self.poll_message(msg, quiet=True)7390divisor = 1000.0 # mm is pretty common in mavlink7391if altitude_source == "SIM_STATE.alt":7392divisor = 1.07393return getattr(msg, field) / divisor73947395def assert_altitude(self, alt, accuracy=1, **kwargs):7396got_alt = self.get_altitude(**kwargs)7397if abs(alt - got_alt) > accuracy:7398raise NotAchievedException("Incorrect alt; want=%f got=%f" %7399(alt, got_alt))74007401def assert_rangefinder_distance_between(self, dist_min, dist_max):7402m = self.assert_receive_message('RANGEFINDER')74037404if m.distance < dist_min:7405raise NotAchievedException("below min height (%f < %f)" %7406(m.distance, dist_min))74077408if m.distance > dist_max:7409raise NotAchievedException("above max height (%f > %f)" %7410(m.distance, dist_max))74117412self.progress(f"Rangefinder distance {m.distance} is between {dist_min} and {dist_max}")74137414def assert_distance_sensor_quality(self, quality):7415m = self.assert_receive_message('DISTANCE_SENSOR')74167417if m.signal_quality != quality:7418raise NotAchievedException("Unexpected quality; want=%f got=%f" %7419(quality, m.signal_quality))74207421def get_rangefinder_distance(self):7422'''returns current rangefinder distance in metres'''7423m = self.assert_receive_message('DISTANCE_SENSOR', timeout=5)7424return m.current_distance * 0.0174257426def wait_rangefinder_distance(self, dist_min, dist_max, timeout=30, **kwargs):7427'''wait for DISTANCE_SENSOR distance in metres'''7428def validator(value2, target2=None):7429if dist_min <= value2 <= dist_max:7430return True7431else:7432return False74337434self.wait_and_maintain(7435value_name="RangeFinderDistance",7436target=dist_min,7437current_value_getter=lambda: self.get_rangefinder_distance(),7438accuracy=(dist_max - dist_min),7439validator=lambda value2, target2: validator(value2, target2),7440timeout=timeout,7441**kwargs7442)74437444def get_esc_rpm(self, esc):7445if esc > 4:7446raise ValueError("Only does 1-4")7447m = self.assert_receive_message('ESC_TELEMETRY_1_TO_4', verbose=True)7448return m.rpm[esc-1]74497450def find_first_set_bit(self, mask):7451'''returns offset of first-set-bit (counting from right) in mask. Returns None if no bits set'''7452pos = 07453while mask != 0:7454if mask & 0x1:7455return pos7456mask = mask >> 17457pos += 17458return None74597460def get_rpm(self, rpm_sensor):7461m = self.assert_receive_message('RPM')7462if rpm_sensor == 1:7463ret = m.rpm17464elif rpm_sensor == 2:7465ret = m.rpm27466else:7467raise ValueError("Bad sensor id")7468if ret < 0.000001:7469# yay filtering!7470return 07471return ret74727473def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs):7474'''wait for RPM to be between rpm_min and rpm_max'''7475def validator(value2, target2=None):7476return rpm_min <= value2 <= rpm_max7477self.wait_and_maintain(7478value_name="RPM%u" % rpm_sensor,7479target=(rpm_min+rpm_max)/2.0,7480current_value_getter=lambda: self.get_rpm(rpm_sensor),7481accuracy=rpm_max-rpm_min,7482validator=lambda value2, target2: validator(value2, target2),7483**kwargs7484)74857486def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):7487'''wait for ESC to be between rpm_min and rpm_max'''7488def validator(value2, target2=None):7489return rpm_min <= value2 <= rpm_max7490self.wait_and_maintain(7491value_name="ESC %u RPM" % esc,7492target=(rpm_min+rpm_max)/2.0,7493current_value_getter=lambda: self.get_esc_rpm(esc),7494accuracy=rpm_max-rpm_min,7495validator=lambda value2, target2: validator(value2, target2),7496**kwargs7497)74987499def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=None, **kwargs):7500"""Wait for a given altitude range."""7501assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude."75027503if timeout is None:7504timeout = 3075057506def validator(value2, target2=None):7507if altitude_min <= value2 <= altitude_max:7508return True7509else:7510return False75117512altitude_source = kwargs.get("altitude_source", None)75137514self.wait_and_maintain(7515value_name="Altitude",7516target=(altitude_min + altitude_max)*0.5,7517current_value_getter=lambda: self.get_altitude(7518relative=relative,7519timeout=timeout,7520altitude_source=altitude_source,7521),7522accuracy=(altitude_max - altitude_min)*0.5,7523validator=lambda value2, target2: validator(value2, target2),7524timeout=timeout,7525**kwargs7526)75277528def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True, altitude_source=None):7529"""Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration"""7530return self.wait_altitude(7531altitude_min=altitude_min,7532altitude_max=altitude_max,7533relative=relative,7534minimum_duration=minimum_duration,7535timeout=minimum_duration + 1,7536altitude_source=altitude_source,7537)75387539def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):7540"""Wait for a given vertical rate."""7541assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."75427543def get_climbrate(timeout2):7544msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)7545return msg.climb75467547def validator(value2, target2=None):7548if speed_min <= value2 <= speed_max:7549return True7550else:7551return False75527553self.wait_and_maintain(7554value_name="Climbrate",7555target=speed_min,7556current_value_getter=lambda: get_climbrate(timeout),7557accuracy=(speed_max - speed_min),7558validator=lambda value2, target2: validator(value2, target2),7559timeout=timeout,7560**kwargs7561)75627563def groundspeed(self):7564m = self.assert_receive_message('VFR_HUD')7565return m.groundspeed75667567def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs):7568self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs)75697570def wait_airspeed(self, speed_min, speed_max, timeout=30, **kwargs):7571self.wait_vfr_hud_speed("airspeed", speed_min, speed_max, timeout=timeout, **kwargs)75727573def wait_vfr_hud_speed(self, field, speed_min, speed_max, timeout=30, **kwargs):7574"""Wait for a given ground speed range."""7575assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."75767577def get_speed(timeout2):7578msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)7579return getattr(msg, field)75807581self.wait_and_maintain_range(7582value_name=field,7583minimum=speed_min,7584maximum=speed_max,7585current_value_getter=lambda: get_speed(timeout),7586validator=None,7587timeout=timeout,7588**kwargs7589)75907591def wait_roll(self, roll, accuracy, timeout=30, absolute_value=False, **kwargs):7592"""Wait for a given roll in degrees."""7593def get_roll(timeout2):7594msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7595p = math.degrees(msg.pitch)7596r = math.degrees(msg.roll)7597if absolute_value:7598r = abs(r)7599self.progress("Roll %d Pitch %d" % (r, p))7600return r76017602def validator(value2, target2):7603return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy76047605self.wait_and_maintain(7606value_name="Roll",7607target=roll,7608current_value_getter=lambda: get_roll(timeout),7609validator=lambda value2, target2: validator(value2, target2),7610accuracy=accuracy,7611timeout=timeout,7612**kwargs7613)76147615def wait_pitch(self, pitch, accuracy, timeout=30, **kwargs):7616"""Wait for a given pitch in degrees."""7617def get_pitch(timeout2):7618msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7619p = math.degrees(msg.pitch)7620r = math.degrees(msg.roll)7621self.progress("Pitch %d Roll %d" % (p, r))7622return p76237624def validator(value2, target2):7625return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy76267627self.wait_and_maintain(7628value_name="Pitch",7629target=pitch,7630current_value_getter=lambda: get_pitch(timeout),7631validator=lambda value2, target2: validator(value2, target2),7632accuracy=accuracy,7633timeout=timeout,7634**kwargs7635)76367637def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs):7638if isinstance(target, Vector3):7639return self.wait_and_maintain_vector(7640value_name,7641target,7642current_value_getter,7643validator,7644timeout=30,7645**kwargs7646)7647return self.wait_and_maintain_range(7648value_name,7649minimum=target - accuracy,7650maximum=target + accuracy,7651current_value_getter=current_value_getter,7652validator=validator,7653timeout=timeout,7654print_diagnostics_as_target_not_range=True,7655**kwargs7656)76577658def wait_and_maintain_vector(self,7659value_name,7660target,7661current_value_getter,7662validator,7663timeout=30,7664**kwargs):7665tstart = self.get_sim_time()7666achieving_duration_start = None7667sum_of_achieved_values = Vector3()7668last_value = Vector3()7669last_fail_print = 07670count_of_achieved_values = 07671called_function = kwargs.get("called_function", None)7672minimum_duration = kwargs.get("minimum_duration", 0)7673if minimum_duration >= timeout:7674raise ValueError("minimum_duration >= timeout")76757676self.progress("Waiting for %s=(%s)" % (value_name, str(target)))76777678last_print_time = 07679while True: # if we failed to received message with the getter the sim time isn't updated # noqa7680now = self.get_sim_time_cached()7681if now - tstart > timeout:7682raise AutoTestTimeoutException(7683"Failed to attain %s want %s, reached %s" %7684(value_name,7685str(target),7686str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) # noqa76877688last_value = current_value_getter()7689if called_function is not None:7690called_function(last_value, target)7691is_value_valid = validator(last_value, target)7692if self.get_sim_time_cached() - last_print_time > 1:7693if is_value_valid:7694want_or_got = "got"7695else:7696want_or_got = "want"7697achieved_duration_bit = ""7698if achieving_duration_start is not None:7699so_far = self.get_sim_time_cached() - achieving_duration_start7700achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)7701self.progress(7702"%s=(%s) (%s (%s))%s" %7703(value_name,7704str(last_value),7705want_or_got,7706str(target),7707achieved_duration_bit)7708)7709last_print_time = self.get_sim_time_cached()7710if is_value_valid:7711sum_of_achieved_values += last_value7712count_of_achieved_values += 1.07713if achieving_duration_start is None:7714achieving_duration_start = self.get_sim_time_cached()7715if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:7716self.progress("Attained %s=%s" % (7717value_name,7718str(sum_of_achieved_values * (1.0 / count_of_achieved_values))))7719return True7720else:7721achieving_duration_start = None7722sum_of_achieved_values.zero()7723count_of_achieved_values = 07724if now - last_fail_print > 1:7725self.progress("Waiting for (%s), got %s" %7726(target, last_value))7727last_fail_print = now77287729def validate_kwargs(self, kwargs, valid: dict | None = None):7730if valid is None:7731valid = {}7732for key in kwargs:7733if key not in valid:7734raise NotAchievedException("Invalid kwarg %s" % str(key))77357736def wait_and_maintain_range(self,7737value_name,7738minimum,7739maximum,7740current_value_getter,7741validator=None,7742value_averager=None,7743timeout=30,7744print_diagnostics_as_target_not_range=False,7745**kwargs):7746self.validate_kwargs(kwargs, valid=frozenset([7747"called_function",7748"minimum_duration",7749"altitude_source",7750]))77517752if print_diagnostics_as_target_not_range:7753target = (minimum + maximum) / 27754accuracy = (maximum - minimum) / 27755tstart = self.get_sim_time()7756achieving_duration_start = None7757sum_of_achieved_values = 0.07758last_value = 0.07759count_of_achieved_values = 07760called_function = kwargs.get("called_function", None)7761minimum_duration = kwargs.get("minimum_duration", 0)7762if minimum_duration >= timeout:7763raise ValueError("minimum_duration >= timeout")7764if print_diagnostics_as_target_not_range:7765self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy))7766else:7767self.progress("Waiting for %s between (%s) and (%s)" % (value_name, str(minimum), str(maximum)))7768last_print_time = 07769while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa7770last_value = current_value_getter()7771if called_function is not None:7772if print_diagnostics_as_target_not_range:7773called_function(last_value, target)7774else:7775called_function(last_value, minimum, maximum)7776if validator is not None:7777if print_diagnostics_as_target_not_range:7778is_value_valid = validator(last_value, target)7779else:7780is_value_valid = validator(last_value, minimum, maximum)7781else:7782is_value_valid = (minimum <= last_value) and (last_value <= maximum)7783if self.get_sim_time_cached() - last_print_time > 1:7784if is_value_valid:7785want_or_got = "got"7786else:7787want_or_got = "want"7788achieved_duration_bit = ""7789if achieving_duration_start is not None:7790so_far = self.get_sim_time_cached() - achieving_duration_start7791achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)77927793if print_diagnostics_as_target_not_range:7794self.progress(7795"%s=%0.2f (%s %f +- %f)%s" %7796(value_name,7797last_value,7798want_or_got,7799target,7800accuracy,7801achieved_duration_bit)7802)7803else:7804if isinstance(last_value, float):7805self.progress(7806"%s=%0.2f (%s between %s and %s)%s" %7807(value_name,7808last_value,7809want_or_got,7810str(minimum),7811str(maximum),7812achieved_duration_bit)7813)7814else:7815self.progress(7816"%s=%s (%s between %s and %s)%s" %7817(value_name,7818last_value,7819want_or_got,7820str(minimum),7821str(maximum),7822achieved_duration_bit)7823)7824last_print_time = self.get_sim_time_cached()7825if is_value_valid:7826if value_averager is not None:7827average = value_averager.add_value(last_value)7828else:7829sum_of_achieved_values += last_value7830count_of_achieved_values += 1.07831average = sum_of_achieved_values / count_of_achieved_values7832if achieving_duration_start is None:7833achieving_duration_start = self.get_sim_time_cached()7834if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:7835self.progress("Attained %s=%s" % (value_name, average))7836return True7837else:7838achieving_duration_start = None7839sum_of_achieved_values = 0.07840count_of_achieved_values = 07841if value_averager is not None:7842value_averager.reset()7843if print_diagnostics_as_target_not_range:7844raise AutoTestTimeoutException(7845"Failed to attain %s want %s, reached %s" %7846(value_name,7847str(target),7848str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))7849else:7850raise AutoTestTimeoutException(7851"Failed to attain %s between %s and %s, reached %s" %7852(value_name,7853str(minimum),7854str(maximum),7855str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))78567857def heading_delta(self, heading1, heading2):7858'''return angle between two 0-360 headings'''7859return math.fabs((heading1 - heading2 + 180) % 360 - 180)78607861def get_heading(self, timeout=1):7862'''return heading 0-359'''7863m = self.assert_receive_message('VFR_HUD', timeout=timeout)7864return m.heading78657866def wait_heading(self, heading, accuracy=5, timeout=30, **kwargs):7867"""Wait for a given heading."""7868def get_heading_wrapped(timeout2):7869return self.get_heading(timeout=timeout2)78707871def validator(value2, target2):7872return self.heading_delta(value2, target2) <= accuracy78737874self.wait_and_maintain(7875value_name="Heading",7876target=heading,7877current_value_getter=lambda: get_heading_wrapped(timeout),7878validator=lambda value2, target2: validator(value2, target2),7879accuracy=accuracy,7880timeout=timeout,7881**kwargs7882)78837884def wait_yaw_speed(self, yaw_speed, accuracy=0.1, timeout=30, **kwargs):7885"""Wait for a given yaw speed in radians per second."""7886def get_yawspeed(timeout2):7887msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)7888return msg.yawspeed78897890def validator(value2, target2):7891return math.fabs(value2 - target2) <= accuracy78927893self.wait_and_maintain(7894value_name="YawSpeed",7895target=yaw_speed,7896current_value_getter=lambda: get_yawspeed(timeout),7897validator=lambda value2, target2: validator(value2, target2),7898accuracy=accuracy,7899timeout=timeout,7900**kwargs7901)79027903def get_speed_vector(self, timeout=1):7904'''return speed vector, NED'''7905msg = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)7906return Vector3(msg.vx, msg.vy, msg.vz)79077908"""Wait for a given speed vector."""7909def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs):7910def validator(value2, target2):7911for (want, got) in (target2.x, value2.x), (target2.y, value2.y), (target2.z, value2.z):7912if want != float("nan") and (math.fabs(got - want) > accuracy):7913return False7914return True79157916self.wait_and_maintain(7917value_name="SpeedVector",7918target=speed_vector,7919current_value_getter=lambda: self.get_speed_vector(timeout=timeout),7920validator=lambda value2, target2: validator(value2, target2),7921accuracy=accuracy,7922timeout=timeout,7923**kwargs7924)79257926def get_descent_rate(self):7927'''get descent rate - a positive number if you are going down'''7928return abs(self.get_speed_vector().z)79297930def wait_descent_rate(self, rate, accuracy=0.1, **kwargs):7931'''wait for descent rate rate, a positive number if going down'''7932def validator(value, target):7933return math.fabs(value - target) <= accuracy79347935self.wait_and_maintain(7936value_name="DescentRate",7937target=rate,7938current_value_getter=lambda: self.get_descent_rate(),7939validator=lambda value, target: validator(value, target),7940accuracy=accuracy,7941**kwargs7942)79437944def get_body_frame_velocity(self):7945gri = self.assert_receive_message('GPS_RAW_INT')7946att = self.assert_receive_message('ATTITUDE')7947return mavextra.gps_velocity_body(gri, att)79487949def wait_speed_vector_bf(self, speed_vector, accuracy=0.2, timeout=30, **kwargs):7950"""Wait for a given speed vector."""7951def get_speed_vector(timeout2):7952return self.get_body_frame_velocity()79537954def validator(value2, target2):7955return (math.fabs(value2.x - target2.x) <= accuracy and7956math.fabs(value2.y - target2.y) <= accuracy and7957math.fabs(value2.z - target2.z) <= accuracy)79587959self.wait_and_maintain(7960value_name="SpeedVectorBF",7961target=speed_vector,7962current_value_getter=lambda: get_speed_vector(timeout),7963validator=lambda value2, target2: validator(value2, target2),7964accuracy=accuracy,7965timeout=timeout,7966**kwargs7967)79687969def wait_distance_between(self, series1, series2, min_distance, max_distance, timeout=30, **kwargs):7970"""Wait for distance between two position series to be between two thresholds."""7971def get_distance():7972self.drain_mav()7973m1 = self.mav.messages[series1]7974m2 = self.mav.messages[series2]7975return self.get_distance_int(m1, m2)79767977self.wait_and_maintain_range(7978value_name=f"Distance({series1}, {series2})",7979minimum=min_distance,7980maximum=max_distance,7981current_value_getter=lambda: get_distance(),7982timeout=timeout,7983**kwargs7984)79857986def wait_distance(self, distance, accuracy=2, timeout=30, **kwargs):7987"""Wait for flight of a given distance."""7988start = self.mav.location()79897990def get_distance():7991return self.get_distance(start, self.mav.location())79927993def validator(value2, target2):7994return math.fabs(value2 - target2) <= accuracy79957996self.wait_and_maintain(7997value_name="Distance",7998target=distance,7999current_value_getter=lambda: get_distance(),8000validator=lambda value2, target2: validator(value2, target2),8001accuracy=accuracy,8002timeout=timeout,8003**kwargs8004)80058006def wait_distance_to_waypoint(self, wp_num, distance_min, distance_max, **kwargs):8007# TODO: use mission_request_partial_list_send8008wps = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)8009m = wps[wp_num]8010self.progress("m: %s" % str(m))8011loc = mavutil.location(m.x / 1.0e7, m.y / 1.0e7, 0, 0)8012self.progress("loc: %s" % str(loc))8013self.wait_distance_to_location(loc, distance_min, distance_max, **kwargs)80148015def wait_distance_to_location(self, location, distance_min, distance_max, timeout=30, **kwargs):8016"""Wait for flight of a given distance."""8017assert distance_min <= distance_max, "Distance min should be less than distance max."80188019def get_distance():8020return self.get_distance(location, self.mav.location())80218022def validator(value2, target2=None):8023return distance_min <= value2 <= distance_max80248025self.wait_and_maintain(8026value_name="Distance",8027target=distance_min,8028current_value_getter=lambda: get_distance(),8029validator=lambda value2, target2: validator(value2, target2),8030accuracy=(distance_max - distance_min), timeout=timeout,8031**kwargs8032)80338034def wait_distance_to_home(self, distance_min, distance_max, timeout=10, use_cached_home=True, **kwargs):8035"""Wait for distance to home to be within specified bounds."""8036assert distance_min <= distance_max, "Distance min should be less than distance max."80378038def get_distance():8039return self.distance_to_home(use_cached_home)80408041def validator(value2, target2=None):8042return distance_min <= value2 <= distance_max80438044self.wait_and_maintain(8045value_name="Distance to home",8046target=distance_min,8047current_value_getter=lambda: get_distance(),8048validator=lambda value2, target2: validator(value2, target2),8049accuracy=(distance_max - distance_min), timeout=timeout,8050**kwargs8051)80528053def assert_at_home(self, accuracy=1):8054if self.distance_to_home() > accuracy:8055raise NotAchievedException("Not at home")80568057def wait_distance_to_nav_target(self,8058distance_min,8059distance_max,8060timeout=10,8061use_cached_nav_controller_output=False,8062**kwargs):8063"""Wait for distance to home to be within specified bounds."""8064assert distance_min <= distance_max, "Distance min should be less than distance max."80658066def get_distance():8067return self.distance_to_nav_target(use_cached_nav_controller_output)80688069def validator(value2, target2=None):8070return distance_min <= value2 <= distance_max80718072self.wait_and_maintain(8073value_name="Distance to nav target",8074target=distance_min,8075current_value_getter=lambda: get_distance(),8076validator=lambda value2,8077target2: validator(value2, target2),8078accuracy=(distance_max - distance_min),8079timeout=timeout,8080**kwargs8081)80828083def get_local_position_NED(self):8084'''return a Vector3 repreesenting vehicle position relative to8085origin in metres, NED'''8086pos = self.assert_receive_message('LOCAL_POSITION_NED')8087return Vector3(pos.x, pos.y, pos.z)80888089def distance_to_local_position(self, local_pos, timeout=30):8090(x, y, z_down) = local_pos # alt is *up*80918092pos = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)80938094delta_x = pos.x - x8095delta_y = pos.y - y8096delta_z = pos.z - z_down8097return math.sqrt(delta_x*delta_x + delta_y*delta_y + delta_z*delta_z)80988099def wait_distance_to_local_position(self,8100local_position, # (x, y, z_down)8101distance_min,8102distance_max,8103timeout=10,8104**kwargs):8105"""Wait for distance to home to be within specified bounds."""8106assert distance_min <= distance_max, "Distance min should be less than distance max."81078108def get_distance():8109return self.distance_to_local_position(local_position)81108111def validator(value2, target2=None):8112return distance_min <= value2 <= distance_max81138114(x, y, z_down) = local_position8115self.wait_and_maintain(8116value_name="Distance to (%f,%f,%f)" % (x, y, z_down),8117target=distance_min,8118current_value_getter=lambda: get_distance(),8119validator=lambda value2,8120target2: validator(value2, target2),8121accuracy=(distance_max - distance_min),8122timeout=timeout,8123**kwargs8124)81258126def wait_parameter_value(self, parameter, value, timeout=10):8127tstart = self.get_sim_time()8128while True:8129if self.get_sim_time_cached() - tstart > timeout:8130raise NotAchievedException("%s never got value %f" %8131(parameter, value))8132v = self.get_parameter(parameter, verbose=False)8133self.progress("Got parameter value (%s=%f)" %8134(parameter, v))8135if v == value:8136return8137self.delay_sim_time(0.1)81388139def wait_parameter_values(self, parameters, timeout=10):8140need_to_see = copy.copy(parameters)8141tstart = self.get_sim_time()8142while True:8143if self.get_sim_time_cached() - tstart > timeout:8144raise NotAchievedException(f"Parameters did not get values: {need_to_see}")8145new_values = self.get_parameters(need_to_see.keys())8146for (n, v) in new_values.items():8147self.progress(f"Got parameter value ({n}={v}) want={need_to_see[n]}")8148if need_to_see[n] == v:8149del need_to_see[n]8150if len(need_to_see) == 0:8151break81528153def get_servo_channel_value(self, channel, timeout=2):8154channel_field = "servo%u_raw" % channel8155tstart = self.get_sim_time()8156while True:8157remaining = timeout - (self.get_sim_time_cached() - tstart)8158if remaining <= 0:8159raise NotAchievedException("Channel value condition not met")8160m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',8161blocking=True,8162timeout=remaining)8163if m is None:8164continue8165m_value = getattr(m, channel_field, None)8166if m_value is None:8167raise ValueError("message (%s) has no field %s" %8168(str(m), channel_field))8169return m_value81708171def wait_servo_channel_value(self, channel, value, epsilon=0, timeout=2, comparator=operator.eq):8172"""wait for channel value comparison (default condition is equality)"""8173channel_field = "servo%u_raw" % channel8174opstring = ("%s" % comparator)[-3:-1]8175tstart = self.get_sim_time()8176while True:8177remaining = timeout - (self.get_sim_time_cached() - tstart)8178if remaining <= 0:8179raise NotAchievedException("Channel value condition not met")8180m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',8181blocking=True,8182timeout=remaining)8183if m is None:8184continue8185m_value = getattr(m, channel_field, None)8186if m_value is None:8187raise ValueError("message (%s) has no field %s" %8188(str(m), channel_field))8189self.progress("SERVO_OUTPUT_RAW.%s got=%u %s want=%u" %8190(channel_field, m_value, opstring, value))8191if comparator == operator.eq:8192if abs(m_value - value) <= epsilon:8193return m_value8194if comparator(m_value, value):8195return m_value81968197def wait_servo_channel_in_range(self, channel, v_min, v_max, timeout=2):8198"""wait for channel value to be within acceptable range"""8199channel_field = "servo%u_raw" % channel8200tstart = self.get_sim_time()8201while True:8202remaining = timeout - (self.get_sim_time_cached() - tstart)8203if remaining <= 0:8204raise NotAchievedException("Channel value condition not met")8205m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',8206blocking=True,8207timeout=remaining)8208if m is None:8209continue8210m_value = getattr(m, channel_field, None)8211if m_value is None:8212raise ValueError("message (%s) has no field %s" %8213(str(m), channel_field))8214self.progress("want %u <= SERVO_OUTPUT_RAW.%s <= %u, got value = %u" %8215(v_min, channel_field, v_max, m_value))8216if (v_min <= m_value) and (m_value <= v_max):8217return m_value82188219def assert_servo_channel_value(self, channel, value, comparator=operator.eq):8220"""assert channel value (default condition is equality)"""8221channel_field = "servo%u_raw" % channel8222opstring = ("%s" % comparator)[-3:-1]8223m = self.assert_receive_message('SERVO_OUTPUT_RAW')8224m_value = getattr(m, channel_field, None)8225if m_value is None:8226raise ValueError("message (%s) has no field %s" %8227(str(m), channel_field))8228self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" %8229(channel_field, m_value, opstring, value))8230if comparator(m_value, value):8231return m_value8232raise NotAchievedException("Wrong value")82338234def assert_servo_channel_range(self, channel, value_min, value_max):8235"""assert channel value is within the range [value_min, value_max]"""8236channel_field = "servo%u_raw" % channel8237m = self.assert_receive_message('SERVO_OUTPUT_RAW')8238m_value = getattr(m, channel_field, None)8239if m_value is None:8240raise ValueError("message (%s) has no field %s" %8241(str(m), channel_field))8242self.progress("assert SERVO_OUTPUT_RAW.%s=%u in [%u, %u]" %8243(channel_field, m_value, value_min, value_max))8244if m_value >= value_min and m_value <= value_max:8245return m_value8246raise NotAchievedException("Wrong value")82478248def get_rc_channel_value(self, channel, timeout=2):8249"""wait for channel to hit value"""8250channel_field = "chan%u_raw" % channel8251tstart = self.get_sim_time()8252while True:8253remaining = timeout - (self.get_sim_time_cached() - tstart)8254if remaining <= 0:8255raise NotAchievedException("Channel never achieved value")8256m = self.mav.recv_match(type='RC_CHANNELS',8257blocking=True,8258timeout=remaining)8259if m is None:8260continue8261m_value = getattr(m, channel_field)8262if m_value is None:8263raise ValueError("message (%s) has no field %s" %8264(str(m), channel_field))8265return m_value82668267def wait_rc_channel_value(self, channel, value, timeout=2):8268channel_field = "chan%u_raw" % channel8269tstart = self.get_sim_time()8270while True:8271remaining = timeout - (self.get_sim_time_cached() - tstart)8272if remaining <= 0:8273raise NotAchievedException("Channel never achieved value")8274m_value = self.get_rc_channel_value(channel, timeout=timeout)8275self.progress("RC_CHANNELS.%s=%u want=%u" %8276(channel_field, m_value, value))8277if value == m_value:8278return82798280def assert_rc_channel_value(self, channel, value):8281channel_field = "chan%u_raw" % channel82828283m_value = self.get_rc_channel_value(channel, timeout=1)8284self.progress("RC_CHANNELS.%s=%u want=%u" %8285(channel_field, m_value, value))8286if value != m_value:8287raise NotAchievedException("Expected %s to be %u got %u" %8288(channel, value, m_value))82898290def send_do_reposition(self,8291loc,8292frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT):8293'''send a DO_REPOSITION command for a location'''8294self.run_cmd_int(8295mavutil.mavlink.MAV_CMD_DO_REPOSITION,82960,82970,82980,82990,8300int(loc.lat*1e7), # lat* 1e78301int(loc.lng*1e7), # lon* 1e78302loc.alt,8303frame=frame8304)83058306def add_rally_point(self, loc, seq, total):8307'''add a rally point at the given location'''8308self.mav.mav.rally_point_send(1, # target system83090, # target component8310seq, # sequence number8311total, # total count8312int(loc.lat * 1e7),8313int(loc.lng * 1e7),8314loc.alt, # relative alt83150, # "break" alt?!83160, # "land dir"83170) # flags83188319def wait_location(self, loc, **kwargs):8320waiter = WaitAndMaintainLocation(self, loc, **kwargs)8321waiter.run()83228323def assert_current_waypoint(self, wpnum):8324seq = self.mav.waypoint_current()8325if seq != wpnum:8326raise NotAchievedException("Incorrect current wp")83278328def wait_current_waypoint(self, wpnum, timeout=70):8329tstart = self.get_sim_time()8330while True:8331if self.get_sim_time() - tstart > timeout:8332raise AutoTestTimeoutException("Did not get wanted current waypoint")8333seq = self.mav.waypoint_current()8334wp_dist = None8335try:8336wp_dist = self.mav.messages['NAV_CONTROLLER_OUTPUT'].wp_dist8337except (KeyError, AttributeError):8338pass8339self.progress("Waiting for wp=%u current=%u dist=%sm" % (wpnum, seq, wp_dist))8340if seq == wpnum:8341break83428343def wait_waypoint(self,8344wpnum_start,8345wpnum_end,8346allow_skip=True,8347max_dist=2,8348timeout=400,8349ignore_RTL_mode_change=False,8350ignore_MANUAL_mode_change=False,8351):8352"""Wait for waypoint ranges."""8353tstart = self.get_sim_time()8354# this message arrives after we set the current WP8355start_wp = self.mav.waypoint_current()8356current_wp = start_wp8357mode = self.mav.flightmode83588359self.progress("wait for waypoint ranges start=%u end=%u"8360% (wpnum_start, wpnum_end))8361# if start_wp != wpnum_start:8362# raise WaitWaypointTimeout("test: Expected start waypoint %u "8363# "but got %u" %8364# (wpnum_start, start_wp))83658366last_wp_msg = 08367while self.get_sim_time_cached() < tstart + timeout:8368seq = self.mav.waypoint_current()8369m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT')8370wp_dist = m.wp_dist8371m = self.assert_receive_message('VFR_HUD')83728373# if we changed mode, fail8374if not self.mode_is('AUTO'):8375self.progress(f"{self.mav.flightmode} vs {self.get_mode_from_mode_mapping(mode)}")8376ignore_mode_change = (8377(ignore_RTL_mode_change and self.mode_is('RTL', cached=True)) or8378(ignore_MANUAL_mode_change and self.mode_is('MANUAL', cached=True))8379)8380if not ignore_mode_change:8381new_mode_str = self.get_mode_string_for_mode(self.get_mode())8382raise WaitWaypointTimeout(f'Exited {mode} mode to {new_mode_str} ignore={ignore_RTL_mode_change}')83838384if self.get_sim_time_cached() - last_wp_msg > 1:8385self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u,"8386"wpnum_end: %u" %8387(seq, wp_dist, m.alt, current_wp, wpnum_end))8388last_wp_msg = self.get_sim_time_cached()8389if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):8390self.progress("WW: Starting new waypoint %u" % seq)8391tstart = self.get_sim_time()8392current_wp = seq8393# the wp_dist check is a hack until we can sort out8394# the right seqnum for end of mission8395# if current_wp == wpnum_end or (current_wp == wpnum_end-1 and8396# wp_dist < 2):8397if current_wp == wpnum_end and wp_dist < max_dist:8398self.progress("Reached final waypoint %u" % seq)8399return True8400if seq >= 255:8401self.progress("Reached final waypoint %u" % seq)8402return True8403if seq > current_wp+1:8404raise WaitWaypointTimeout(("Skipped waypoint! Got wp %u expected %u"8405% (seq, current_wp+1)))8406raise WaitWaypointTimeout("Timed out waiting for waypoint %u of %u" %8407(wpnum_end, wpnum_end))84088409def get_cached_message(self, message_type):8410'''returns the most-recently received instance of message_type'''8411return self.mav.messages[message_type]84128413def mode_is(self, mode, cached=False, drain_mav=True, drain_mav_quietly=True):8414if not cached:8415self.wait_heartbeat(drain_mav=drain_mav, quiet=drain_mav_quietly)8416return self.mav.messages['HEARTBEAT'].custom_mode == self.get_mode_from_mode_mapping(mode)84178418def wait_mode(self, mode, timeout=60):8419"""Wait for mode to change."""8420self.progress("Waiting for mode %s" % mode)8421tstart = self.get_sim_time()8422while not self.mode_is(mode, drain_mav=False):8423custom_num = self.mav.messages['HEARTBEAT'].custom_mode8424self.progress("mav.flightmode=%s Want=%s custom=%u" % (8425self.mav.flightmode, mode, custom_num))8426if (timeout is not None and8427self.get_sim_time_cached() > tstart + timeout):8428raise WaitModeTimeout("Did not change mode")8429self.progress("Got mode %s" % mode)84308431def assert_mode_is(self, mode):8432if not self.mode_is(mode):8433raise NotAchievedException("Expected mode %s" % str(mode))84348435def get_mode(self, cached=False, drain_mav=True):8436'''return numeric custom mode'''8437if not cached:8438self.wait_heartbeat(drain_mav=drain_mav)8439return self.mav.messages['HEARTBEAT'].custom_mode84408441def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30):8442self.progress("Waiting for GPS health")8443tstart = self.get_sim_time()8444while True:8445now = self.get_sim_time_cached()8446if now - tstart > timeout:8447raise AutoTestTimeoutException("GPS status bits did not become good")8448m = self.mav.recv_match(type='SYS_STATUS', blocking=True, timeout=1)8449if m is None:8450continue8451if (not (m.onboard_control_sensors_present & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8452self.progress("GPS not present")8453if now > 20:8454# it's had long enough to be detected....8455return8456continue8457if (not (m.onboard_control_sensors_enabled & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8458self.progress("GPS not enabled")8459continue8460if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):8461self.progress("GPS not healthy")8462continue8463self.progress("GPS healthy after %f/%f seconds" %8464((now - tstart), timeout))8465return84668467def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False):8468return self.sensor_has_state(sensor, present, enabled, healthy, do_assert=True, verbose=verbose)84698470def sensor_has_state(self, sensor, present=True, enabled=True, healthy=True, do_assert=False, verbose=False):8471m = self.assert_receive_message('SYS_STATUS', timeout=5, very_verbose=verbose)8472reported_present = m.onboard_control_sensors_present & sensor8473reported_enabled = m.onboard_control_sensors_enabled & sensor8474reported_healthy = m.onboard_control_sensors_health & sensor8475if present:8476if not reported_present:8477if do_assert:8478raise NotAchievedException("Sensor not present")8479return False8480else:8481if reported_present:8482if do_assert:8483raise NotAchievedException("Sensor present when it shouldn't be")8484return False84858486if enabled:8487if not reported_enabled:8488if do_assert:8489raise NotAchievedException("Sensor not enabled")8490return False8491else:8492if reported_enabled:8493if do_assert:8494raise NotAchievedException("Sensor enabled when it shouldn't be")8495return False84968497if healthy:8498if not reported_healthy:8499if do_assert:8500raise NotAchievedException("Sensor not healthy")8501return False8502else:8503if reported_healthy:8504if do_assert:8505raise NotAchievedException("Sensor healthy when it shouldn't be")8506return False8507return True85088509def wait_sensor_state(self, sensor, present=True, enabled=True, healthy=True, timeout=5, verbose=False):8510tstart = self.get_sim_time()8511while True:8512if self.get_sim_time_cached() - tstart > timeout:8513raise NotAchievedException("Sensor did not achieve state")8514if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose):8515break85168517def wait_not_ready_to_arm(self):8518self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False)85198520def wait_prearm_sys_status_healthy(self, timeout=60):8521self.do_timesync_roundtrip()8522tstart = self.get_sim_time()8523while True:8524t2 = self.get_sim_time_cached()8525if t2 - tstart > timeout:8526self.progress("Prearm bit never went true. Attempting arm to elicit reason from autopilot")8527try:8528self.arm_vehicle()8529except Exception:8530pass8531raise AutoTestTimeoutException("Prearm bit never went true")8532if self.sensor_has_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, True):8533break85348535def assert_fence_enabled(self, timeout=2):8536# Check fence is enabled8537m = self.assert_receive_message('FENCE_STATUS', timeout=timeout)8538self.progress("Got (%s)" % str(m))85398540def assert_fence_disabled(self, timeout=2):8541# Check fence is not enabled8542self.assert_not_receiving_message('FENCE_STATUS', timeout=timeout)85438544def NoArmWithoutMissionItems(self):8545'''ensure we can't arm in auto mode without mission items present'''8546# load a trivial mission8547items = []8548items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 20000),)8549items.append((mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0))8550self.upload_simple_relhome_mission(items)85518552self.change_mode('AUTO')8553self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)8554self.assert_prearm_failure('Mode requires mission',8555other_prearm_failures_fatal=False)85568557def assert_prearm_failure(self,8558expected_statustext,8559timeout=5,8560ignore_prearm_failures: list | None = None,8561other_prearm_failures_fatal=True):8562if ignore_prearm_failures is None:8563ignore_prearm_failures = []85648565seen_statustext = False8566seen_command_ack = False85678568self.drain_mav()8569tstart = self.get_sim_time_cached()8570arm_last_send = 08571while True:8572if seen_command_ack and seen_statustext:8573break8574now = self.get_sim_time_cached()8575if now - tstart > timeout:8576raise NotAchievedException(8577f"Did not see failure-to-arm messages ({seen_statustext=} {expected_statustext=} {seen_command_ack=})"8578)8579if now - arm_last_send > 1:8580arm_last_send = now8581self.send_mavlink_run_prearms_command()8582m = self.mav.recv_match(blocking=True, timeout=1)8583if m is None:8584continue8585if m.get_type() == "STATUSTEXT":8586if expected_statustext in m.text:8587self.progress("Got: %s" % str(m))8588seen_statustext = True8589elif other_prearm_failures_fatal and "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:8590self.progress("Got: %s" % str(m))8591raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)85928593if m.get_type() == "COMMAND_ACK":8594print("Got: %s" % str(m))8595if m.command == mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS:8596if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:8597raise NotAchievedException("command-ack says we didn't run prearms")8598self.progress("Got: %s" % str(m))8599seen_command_ack = True8600if self.mav.motors_armed():8601raise NotAchievedException("Armed when we shouldn't have")86028603def assert_arm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures: list = None):8604if ignore_prearm_failures is None:8605ignore_prearm_failures = []8606seen_statustext = False8607seen_command_ack = False86088609self.drain_mav()8610tstart = self.get_sim_time_cached()8611arm_last_send = 08612while True:8613if seen_command_ack and seen_statustext:8614break8615now = self.get_sim_time_cached()8616if now - tstart > timeout:8617raise NotAchievedException(8618"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %8619(seen_statustext, seen_command_ack))8620if now - arm_last_send > 1:8621arm_last_send = now8622self.send_mavlink_arm_command()8623m = self.mav.recv_match(blocking=True, timeout=1)8624if m is None:8625continue8626if m.get_type() == "STATUSTEXT":8627if expected_statustext in m.text:8628self.progress("Got: %s" % str(m))8629seen_statustext = True8630elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:8631self.progress("Got: %s" % str(m))8632raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)86338634if m.get_type() == "COMMAND_ACK":8635print("Got: %s" % str(m))8636if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:8637if m.result != 4:8638raise NotAchievedException("command-ack says we didn't fail to arm")8639self.progress("Got: %s" % str(m))8640seen_command_ack = True8641if self.mav.motors_armed():8642raise NotAchievedException("Armed when we shouldn't have")86438644def wait_ready_to_arm(self, timeout=120, require_absolute=True, check_prearm_bit=True):8645# wait for EKF checks to pass8646self.progress("Waiting for ready to arm")8647start = self.get_sim_time()8648self.wait_ekf_happy(timeout=timeout, require_absolute=require_absolute)8649if require_absolute:8650self.wait_gps_sys_status_not_present_or_enabled_and_healthy()8651if require_absolute:8652self.poll_home_position()8653if check_prearm_bit:8654self.wait_prearm_sys_status_healthy(timeout=timeout)8655armable_time = self.get_sim_time() - start8656self.progress("Took %u seconds to become armable" % armable_time)8657self.total_waiting_to_arm_time += armable_time8658self.waiting_to_arm_count += 186598660def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x):8661'''as opposed to mav.wait_heartbeat, raises an exception on timeout.8662Also, ignores heartbeats not from our target system'''8663if drain_mav:8664self.drain_mav(quiet=quiet)8665orig_timeout = x.get("timeout", 20)8666x["timeout"] = 18667tstart = time.time()8668while True:8669if time.time() - tstart > orig_timeout and not self.gdb:8670if not self.sitl_is_running():8671self.progress("SITL is not running")8672raise AutoTestTimeoutException("Did not receive heartbeat")8673m = self.mav.wait_heartbeat(*args, **x)8674if m is None:8675continue8676if m.get_srcSystem() == self.sysid_thismav():8677return m86788679def wait_ekf_happy(self, require_absolute=True, **kwargs):8680"""Wait for EKF to be happy"""8681if "timeout" not in kwargs:8682kwargs["timeout"] = 4586838684""" if using SITL estimates directly """8685if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):8686return True86878688# all of these must be set for arming to happen:8689required_value = (mavutil.mavlink.EKF_ATTITUDE |8690mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ |8691mavutil.mavlink.ESTIMATOR_VELOCITY_VERT |8692mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL |8693mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_REL)8694# none of these bits must be set for arming to happen:8695error_bits = (mavutil.mavlink.ESTIMATOR_CONST_POS_MODE |8696mavutil.mavlink.ESTIMATOR_ACCEL_ERROR)8697if require_absolute:8698required_value |= (mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS |8699mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |8700mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)8701error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH8702WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()87038704def wait_ekf_flags(self, required_value, error_bits, **kwargs):8705WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()87068707def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):8708"""Disable GPS and wait for EKF to report the end of assistance from GPS."""8709self.set_parameter("SIM_GPS1_ENABLE", 0)8710tstart = self.get_sim_time()87118712""" if using SITL estimates directly """8713if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):8714self.progress("GPS disable skipped")8715return87168717# all of these must NOT be set for arming NOT to happen:8718not_required_value = 08719if position_horizontal:8720not_required_value |= mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL8721if position_vertical:8722not_required_value |= mavutil.mavlink.ESTIMATOR_POS_VERT_AGL8723self.progress("Waiting for EKF not having bits %u" % not_required_value)8724last_print_time = 08725while timeout is None or self.get_sim_time_cached() < tstart + timeout:8726esr = self.assert_receive_message('EKF_STATUS_REPORT', timeout=timeout)8727current = esr.flags8728if self.get_sim_time_cached() - last_print_time > 1:8729self.progress("Wait EKF.flags: not required:%u current:%u" %8730(not_required_value, current))8731last_print_time = self.get_sim_time_cached()8732if current & not_required_value != not_required_value:8733self.progress("GPS disable OK")8734return8735self.progress(f"Last EKF_STATUS_REPORT: {esr}")8736raise AutoTestTimeoutException("Failed to get EKF.flags=%u disabled" % not_required_value)87378738def wait_text(self, *args, **kwargs):8739'''wait for text to appear from vehicle, return that text'''8740statustext = self.wait_statustext(*args, **kwargs)8741if statustext is None:8742return None8743return statustext.text87448745def statustext_in_collections(self, text, regex=False):8746'''searches for text in STATUSTEXT collection, returns message if found'''8747c = self.context_get()8748if "STATUSTEXT" not in c.collections:8749raise NotAchievedException("Asked to check context but it isn't collecting!")8750for x in c.collections["STATUSTEXT"]:8751self.progress(" statustext got=(%s) want=(%s)" % (x.text, text))8752if regex:8753if re.match(text, x.text):8754return x8755elif text.lower() in x.text.lower():8756return x8757return None87588759def wait_statustext(self, text, timeout=20, the_function=None, check_context=False, regex=False, wallclock_timeout=False):8760"""Wait for a specific STATUSTEXT, return that statustext message"""87618762# Statustexts are often triggered by something we've just8763# done, so we have to be careful not to read any traffic that8764# isn't checked for being our statustext. That doesn't work8765# well with getting the current simulation time (which requires8766# a new SYSTEM_TIME message), so we install a message hook8767# which checks all incoming messages.8768self.progress("Waiting for text : %s" % text.lower())8769if check_context:8770statustext = self.statustext_in_collections(text, regex=regex)8771if statustext:8772self.progress("Found expected text in collection: %s" % text.lower())8773return statustext87748775global statustext_found8776global statustext_full8777statustext_full = None8778statustext_found = False87798780def mh(mav, m):8781global statustext_found8782global statustext_full8783if m.get_type() != "STATUSTEXT":8784return8785if regex:8786self.re_match = re.match(text, m.text)8787if self.re_match:8788statustext_found = True8789statustext_full = m8790if text.lower() in m.text.lower():8791self.progress("Received expected text: %s" % m.text.lower())8792statustext_found = True8793statustext_full = m87948795self.install_message_hook(mh)8796if wallclock_timeout:8797tstart = time.time()8798else:8799tstart = self.get_sim_time()8800try:8801while not statustext_found:8802if wallclock_timeout:8803now = time.time()8804else:8805now = self.get_sim_time_cached()8806if now - tstart > timeout:8807raise AutoTestTimeoutException("Failed to receive text: %s" %8808text.lower())8809if the_function is not None:8810the_function()8811self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)8812finally:8813self.remove_message_hook(mh)8814return statustext_full88158816# routines helpful for testing LUA scripting:8817def script_example_source_path(self, scriptname):8818return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "examples", scriptname)88198820def script_test_source_path(self, scriptname):8821return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", scriptname)88228823def script_applet_source_path(self, scriptname):8824return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "applets", scriptname)88258826def script_modules_source_path(self, scriptname):8827return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "modules", scriptname)88288829def installed_script_path(self, scriptname):8830return os.path.join("scripts", os.path.basename(scriptname))88318832def install_script(self, source, scriptname, install_name=None):8833if install_name is not None:8834dest = self.installed_script_path(install_name)8835else:8836dest = self.installed_script_path(scriptname)88378838destdir = os.path.dirname(dest)8839if not os.path.exists(destdir):8840os.mkdir(destdir)8841self.progress("Copying (%s) to (%s)" % (source, dest))8842shutil.copy(source, dest)88438844def installed_script_module_path(self, modulename):8845return os.path.join("scripts", "modules", os.path.basename(modulename))88468847def install_script_module(self, source, modulename, install_name=None):8848if install_name is not None:8849dest = self.installed_script_module_path(install_name)8850else:8851dest = self.installed_script_module_path(modulename)88528853destdir = os.path.dirname(dest)8854os.makedirs(destdir, exist_ok=True)8855self.progress("Copying (%s) to (%s)" % (source, dest))8856shutil.copy(source, dest)88578858def install_test_modules(self):8859source = os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", "modules", "test")8860dest = os.path.join("scripts", "modules", "test")8861self.progress("Copying (%s) to (%s)" % (source, dest))8862shutil.copytree(source, dest)88638864def install_mavlink_module(self):8865dest = os.path.join("scripts", "modules", "mavlink")8866ardupilotmega_xml = os.path.join(self.rootdir(), "modules", "mavlink",8867"message_definitions", "v1.0", "ardupilotmega.xml")8868mavgen.mavgen(mavgen.Opts(output=dest, wire_protocol='2.0', language='Lua'), [ardupilotmega_xml])8869self.progress("Installed mavlink module")88708871def install_script_content(self, scriptname, content):8872dest = self.installed_script_path(scriptname)8873destdir = os.path.dirname(dest)8874if not os.path.exists(destdir):8875os.mkdir(destdir)8876destPath = pathlib.Path(dest)8877destPath.write_text(content)88788879def install_example_script(self, scriptname):8880source = self.script_example_source_path(scriptname)8881self.install_script(source, scriptname)88828883def install_test_script(self, scriptname):8884source = self.script_test_source_path(scriptname)8885self.install_script(source, scriptname)88868887def install_applet_script(self, scriptname, install_name=None):8888source = self.script_applet_source_path(scriptname)8889self.install_script(source, scriptname, install_name=install_name)88908891def remove_installed_script(self, scriptname):8892dest = self.installed_script_path(os.path.basename(scriptname))8893try:8894os.unlink(dest)8895except IOError:8896pass8897except OSError:8898pass88998900def remove_installed_script_module(self, modulename):8901path = self.installed_script_module_path(modulename)8902os.unlink(path)89038904def remove_installed_modules(self, modulename):8905dest = os.path.join("scripts", "modules", modulename)8906try:8907shutil.rmtree(dest)8908except IOError:8909pass8910except OSError:8911pass89128913def get_mavlink_connection_going(self):8914# get a mavlink connection going8915try:8916retries = 208917if self.gdb:8918retries = 200008919self.mav = mavutil.mavlink_connection(8920self.autotest_connection_string_to_ardupilot(),8921retries=retries,8922robust_parsing=True,8923source_system=250,8924source_component=250,8925autoreconnect=True,8926dialect="all", # if we don't pass this in we end up with the wrong mavlink version...8927)8928except Exception as msg:8929self.progress("Failed to start mavlink connection on %s: %s" %8930(self.autotest_connection_string_to_ardupilot(), msg,))8931raise8932self.mav.message_hooks.append(self.message_hook)8933self.mav.mav.set_send_callback(self.send_message_hook, self)8934self.mav.idle_hooks.append(self.idle_hook)89358936# we need to wait for a heartbeat here. If we don't then8937# self.mav.target_system will be zero because it hasn't8938# "locked on" to a target system yet.8939self.wait_heartbeat()8940self.set_streamrate(self.sitl_streamrate())89418942def show_test_timings_key_sorter(self, t):8943(k, v) = t8944return ((v, k))89458946def show_test_timings(self):8947if len(self.test_timings.keys()) == 0:8948return8949longest = 08950for desc in self.test_timings.keys():8951if len(desc) > longest:8952longest = len(desc)8953tests_total_time = 08954for desc, test_time in sorted(self.test_timings.items(),8955key=self.show_test_timings_key_sorter):8956fmt = "%" + str(longest) + "s: %.2fs"8957tests_total_time += test_time8958self.progress(fmt % (desc, test_time))8959self.progress(fmt % ("**--tests_total_time--**", tests_total_time))8960self.progress("mavproxy_start was called %u times" %8961(self.start_mavproxy_count,))8962self.progress("Supplied terrain data to autopilot in %u messages" %8963(self.terrain_data_messages_sent,))89648965def send_statustext(self, text):8966if not isinstance(text, bytes):8967text = bytes(text, "ascii")8968seq = 08969while len(text):8970self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text[:50], id=self.statustext_id, chunk_seq=seq)8971text = text[50:]8972seq += 18973self.statustext_id += 18974if self.statustext_id > 255:8975self.statustext_id = 189768977def get_stacktrace(self):8978return ''.join(traceback.format_stack())89798980def get_exception_stacktrace(self, e):8981ret = "%s\n" % e8982ret += ''.join(traceback.format_exception(type(e),8983e,8984tb=e.__traceback__))8985return ret89868987def bin_logs(self):8988return glob.glob("logs/*.BIN")89898990def remove_bin_logs(self):8991util.run_cmd('rm -f logs/*.BIN logs/LASTLOG.TXT')89928993def remove_ardupilot_terrain_cache(self):8994'''removes the terrain files ArduPilot keeps in its onboiard storage'''8995util.run_cmd('rm -f %s' % util.reltopdir("terrain/*.DAT"))89968997def check_logs(self, name, bin_logs=None):8998'''called to move relevant log files from our working directory to the8999buildlogs directory'''9000if not self.move_logs_on_test_failure:9001return9002to_dir = self.logs_dir9003# move telemetry log files9004for log in glob.glob("autotest-*.tlog"):9005bname = os.path.basename(log)9006newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))9007print("Renaming %s to %s" % (log, newname))9008shutil.move(log, newname)9009# move binary log files9010if bin_logs is None:9011bin_logs = self.bin_logs()9012for log in sorted(bin_logs):9013bname = os.path.basename(log)9014newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))9015print("Renaming %s to %s" % (log, newname))9016shutil.move(log, newname)9017# move core files9018save_binaries = False9019corefiles = []9020corefiles.extend(glob.glob("core*"))9021corefiles.extend(glob.glob("ap-*.core"))9022for log in sorted(corefiles):9023bname = os.path.basename(log)9024newname = os.path.join(to_dir, "%s-%s-%s" % (bname, self.log_name(), name))9025print("Renaming %s to %s" % (log, newname))9026shutil.move(log, newname)9027save_binaries = True9028if save_binaries:9029util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir,9030directory=util.reltopdir('.'))90319032def run_one_test(self, test, interact=False, suppress_stdout=False):9033'''new-style run-one-test used by run_tests'''9034for i in range(0, test.attempts-1):9035result = self.run_one_test_attempt(test, interact=interact, attempt=i+2, suppress_stdout=suppress_stdout)9036if result.passed:9037return result9038self.progress("Run attempt failed. Retrying")9039return self.run_one_test_attempt(test, interact=interact, attempt=1, suppress_stdout=suppress_stdout)90409041def print_exception_caught(self, e, send_statustext=True):9042self.progress("Exception caught: %s" %9043self.get_exception_stacktrace(e))9044path = None9045try:9046path = self.current_onboard_log_filepath()9047except IndexError:9048pass9049self.progress("Most recent logfile: %s" % (path, ), send_statustext=send_statustext)90509051def progress_file_content(self, filepath):9052with open(filepath) as f:9053for line in f:9054self.progress(line.rstrip())90559056def dump_process_status(self, result):9057'''used to show where the SITL process is upto. Often caused when9058we've lost contact'''90599060if self.sitl.isalive():9061self.progress("pexpect says it is alive")9062for tool in "dumpstack.sh", "dumpcore.sh":9063tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)9064if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:9065reason = "Failed %s" % (tool,)9066self.progress(reason)9067result.reason = reason9068result.passed = False9069else:9070self.progress("pexpect says it is dead")90719072# try dumping the process status file for more information:9073status_filepath = "/proc/%u/status" % self.sitl.pid9074self.progress("Checking for status filepath (%s)" % status_filepath)9075if os.path.exists(status_filepath):9076self.progress_file_content(status_filepath)9077else:9078self.progress("... does not exist")90799080def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=False):9081'''called by run_one_test to actually run the test in a retry loop'''9082name = test.name9083desc = test.description9084test_function = test.function9085test_kwargs = test.kwargs9086if attempt != 1:9087self.progress("RETRYING %s" % name)9088test_output_filename = self.buildlogs_path("%s-%s-retry-%u.txt" %9089(self.log_name(), name, attempt-1))9090else:9091test_output_filename = self.buildlogs_path("%s-%s.txt" %9092(self.log_name(), name))90939094tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)90959096start_message_hooks = copy.copy(self.message_hooks)90979098prettyname = "%s (%s)" % (name, desc)9099self.start_test(prettyname)9100self.set_current_test_name(name)9101old_contexts_length = len(self.contexts)9102self.context_push()91039104start_time = time.time()91059106orig_speedup = None91079108hooks_removed = False91099110ex = None9111try:9112self.check_rc_defaults()9113self.change_mode(self.default_mode())9114# ArduPilot can still move the current waypoint from 0,9115# even if we are not in AUTO mode, so cehck_afterwards=False:9116self.set_current_waypoint(0, check_afterwards=False)9117self.drain_mav()9118self.drain_all_pexpects()9119if test.speedup is not None:9120self.progress("Overriding speedup to %u" % test.speedup)9121orig_speedup = self.get_parameter("SIM_SPEEDUP")9122self.set_parameter("SIM_SPEEDUP", test.speedup)91239124test_function(**test_kwargs)9125except Exception as e:9126self.print_exception_caught(e)9127ex = e9128# reset the message hooks; we've failed-via-exception and9129# can't expect the hooks to have been cleaned up9130for h in copy.copy(self.message_hooks):9131if h not in start_message_hooks:9132self.message_hooks.remove(h)9133hooks_removed = True9134self.test_timings[desc] = time.time() - start_time9135reset_needed = self.contexts[-1].sitl_commandline_customised91369137if orig_speedup is not None:9138self.set_parameter("SIM_SPEEDUP", orig_speedup)91399140passed = True9141if ex is not None:9142passed = False91439144result = Result(test)9145result.time_elapsed = self.test_timings[desc]91469147ardupilot_alive = False9148try:9149self.wait_heartbeat()9150ardupilot_alive = True9151except Exception:9152# process is dead9153self.progress("No heartbeat after test", send_statustext=False)9154self.dump_process_status(result)91559156passed = False9157reset_needed = True91589159try:9160self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)9161except Exception as e:9162self.print_exception_caught(e, send_statustext=False)9163passed = False91649165pre_reboot_bin_logs = self.bin_logs()91669167# if we haven't already reset ArduPilot because it's dead,9168# then ensure the vehicle was disarmed at the end of the test.9169# If it wasn't then the test is considered failed:9170if ardupilot_alive and self.armed() and not self.is_tracker():9171if ex is None:9172ex = ArmedAtEndOfTestException("Still armed at end of test")9173self.progress("Armed at end of test; force-rebooting SITL")9174self.set_rc_default() # otherwise we might start calibrating ESCs...9175try:9176self.disarm_vehicle(force=True)9177except AutoTestTimeoutException:9178reset_needed = True9179self.forced_post_test_sitl_reboots += 19180if reset_needed:9181self.progress("Force-resetting SITL")9182self.reset_SITL_commandline()9183else:9184self.progress("Force-rebooting SITL")9185self.zero_throttle()9186self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it9187passed = False9188elif ardupilot_alive and not passed: # implicit reboot after a failed test:9189self.progress("Test failed but ArduPilot process alive; rebooting")9190self.reboot_sitl() # that'll learn it91919192if self._mavproxy is not None:9193self.progress("Stopping auto-started mavproxy")9194if self.use_map:9195self.mavproxy.send("module unload map\n")9196self.mavproxy.expect("Unloaded module map")91979198self.expect_list_remove(self._mavproxy)9199util.pexpect_close(self._mavproxy)9200self._mavproxy = None92019202corefiles = []9203corefiles.extend(glob.glob("core*"))9204corefiles.extend(glob.glob("ap-*.core"))9205if corefiles:9206self.progress('Corefiles detected: %s' % str(corefiles))9207passed = False92089209if len(self.contexts) != old_contexts_length:9210self.progress("context count mismatch (want=%u got=%u); popping extras" %9211(old_contexts_length, len(self.contexts)))9212passed = False9213# pop off old contexts to clean up message hooks etc9214while len(self.contexts) > old_contexts_length:9215try:9216self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)9217except Exception as e:9218self.print_exception_caught(e, send_statustext=False)9219self.progress("Done popping extra contexts")92209221# make sure we don't leave around stray listeners:9222if len(self.message_hooks) != len(start_message_hooks):9223self.progress("Stray message listeners: %s vs start %s" %9224(str(self.message_hooks), str(start_message_hooks)))9225passed = False92269227if passed:9228# 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. # noqa9229pass9230else:9231if self.logs_dir is not None:9232# stash the binary logs and corefiles away for later analysis9233self.check_logs(name, bin_logs=pre_reboot_bin_logs)92349235if passed:9236self.progress('PASSED: "%s"' % prettyname)9237else:9238self.progress('FAILED: "%s": %s (see %s)' %9239(prettyname, repr(ex), test_output_filename))9240result.exception = ex9241result.debug_filename = test_output_filename9242if interact:9243self.progress("Starting MAVProxy interaction as directed")9244self.mavproxy.interact()92459246if self.reset_after_every_test:9247reset_needed = True92489249if reset_needed:9250self.reset_SITL_commandline()92519252if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling9253self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)9254self.set_current_waypoint(0, check_afterwards=False)92559256tee.close()92579258result.passed = passed9259return result92609261def defaults_filepath(self):9262return None92639264def start_mavproxy(self, sitl_rcin_port=None, master=None, options=None):9265self.start_mavproxy_count += 19266if self.mavproxy is not None:9267return self.mavproxy9268self.progress("Starting MAVProxy")92699270# determine a good pexpect timeout for reading MAVProxy's9271# output; some regmes may require longer timeouts.9272pexpect_timeout = 609273if self.valgrind or self.callgrind:9274pexpect_timeout *= 1092759276if sitl_rcin_port is None:9277sitl_rcin_port = self.sitl_rcin_port()92789279if master is None:9280master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762)92819282if options is None:9283options = self.mavproxy_options()9284else:9285op = self.mavproxy_options().copy()9286op.extend(options)9287options = op92889289mavproxy = util.start_MAVProxy_SITL(9290self.vehicleinfo_key(),9291master=master,9292logfile=self.mavproxy_logfile,9293options=options,9294pexpect_timeout=pexpect_timeout,9295sitl_rcin_port=sitl_rcin_port,9296)9297mavproxy.expect(r'Telemetry log: (\S+)\r\n')9298self.logfile = mavproxy.match.group(1)9299self.progress("LOGFILE %s" % self.logfile)9300self.try_symlink_tlog()93019302self.expect_list_add(mavproxy)9303util.expect_setup_callback(mavproxy, self.expect_callback)9304self._mavproxy = mavproxy # so we can clean up after tests....9305return mavproxy93069307def stop_mavproxy(self, mavproxy):9308if self.mavproxy is not None:9309return9310self.progress("Stopping MAVProxy")9311self.expect_list_remove(mavproxy)9312util.pexpect_close(mavproxy)9313self._mavproxy = None93149315def start_SITL(self, binary=None, sitl_home=None, **sitl_args):9316if sitl_home is None:9317sitl_home = self.sitl_home()9318start_sitl_args = {9319"breakpoints": self.breakpoints,9320"disable_breakpoints": self.disable_breakpoints,9321"gdb": self.gdb,9322"gdb_no_tui": self.gdb_no_tui,9323"gdbserver": self.gdbserver,9324"lldb": self.lldb,9325"strace": self.strace,9326"home": sitl_home,9327"speedup": self.speedup,9328"valgrind": self.valgrind,9329"callgrind": self.callgrind,9330"wipe": True,9331"enable_fgview": self.enable_fgview,9332}9333start_sitl_args.update(**sitl_args)9334if ("defaults_filepath" not in start_sitl_args or9335start_sitl_args["defaults_filepath"] is None):9336start_sitl_args["defaults_filepath"] = self.defaults_filepath()93379338if "model" not in start_sitl_args or start_sitl_args["model"] is None:9339start_sitl_args["model"] = self.frame9340self.progress("Starting SITL", send_statustext=False)9341if binary is None:9342binary = self.binary9343self.sitl = util.start_SITL(binary, **start_sitl_args)9344self.expect_list_add(self.sitl)9345self.sup_prog = []9346count = 09347for sup_binary in self.sup_binaries:9348self.progress("Starting Supplementary Program ", sup_binary)9349start_sitl_args["customisations"] = [sup_binary['customisation']]9350start_sitl_args["supplementary"] = True9351start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count)9352start_sitl_args["defaults_filepath"] = sup_binary['param_file']9353sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)9354self.sup_prog.append(sup_prog_link)9355self.expect_list_add(sup_prog_link)9356count += 193579358# mavlink will have disconnected here. Explicitly reconnect,9359# or the first packet we send will be lost:9360if self.mav is not None:9361self.mav.reconnect()93629363def get_supplementary_programs(self):9364return self.sup_prog93659366def stop_sup_program(self, instance=None):9367self.progress("Stopping supplementary program")9368if instance is None:9369# close all sup programs9370for prog in self.sup_prog:9371self.expect_list_remove(prog)9372self.sup_prog.remove(prog)9373util.pexpect_close(prog)9374else:9375# close only the instance passed9376prog = self.sup_prog[instance]9377self.expect_list_remove(prog)9378self.sup_prog[instance] = None9379util.pexpect_close(prog)93809381def start_sup_program(self, instance=None, args=None):9382self.progress("Starting supplementary program")9383start_sitl_args = {9384"breakpoints": self.breakpoints,9385"disable_breakpoints": self.disable_breakpoints,9386"gdb": self.gdb,9387"gdb_no_tui": self.gdb_no_tui,9388"gdbserver": self.gdbserver,9389"lldb": self.lldb,9390"strace": self.strace,9391"home": self.sitl_home(),9392"speedup": self.speedup,9393"valgrind": self.valgrind,9394"callgrind": self.callgrind,9395"wipe": True,9396}9397for i in range(len(self.sup_binaries)):9398if instance is not None and instance != i:9399continue9400sup_binary = self.sup_binaries[i]9401start_sitl_args["customisations"] = [sup_binary['customisation']]9402if args is not None:9403start_sitl_args["customisations"] = [sup_binary['customisation'], args]9404start_sitl_args["supplementary"] = True9405start_sitl_args["defaults_filepath"] = sup_binary['param_file']9406sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)9407time.sleep(1)9408self.sup_prog[i] = sup_prog_link # add to list9409self.expect_list_add(sup_prog_link) # add to expect list94109411def sitl_is_running(self):9412if self.sitl is None:9413return False9414return self.sitl.isalive()94159416def autostart_mavproxy(self):9417return self.use_map94189419def init(self):9420"""Initialize autotest feature."""9421self.mavproxy_logfile = self.open_mavproxy_logfile()94229423if self.frame is None:9424self.frame = self.default_frame()94259426if self.frame is None:9427raise ValueError("frame must not be None")94289429self.progress("Starting simulator")9430self.start_SITL()94319432os.environ['MAVLINK20'] = '1'94339434self.progress("Starting MAVLink connection")9435self.get_mavlink_connection_going()94369437if self.autostart_mavproxy():9438self.mavproxy = self.start_mavproxy()94399440self.expect_list_clear()9441self.expect_list_extend([self.sitl, self.mavproxy])9442self.expect_list_extend(self.sup_prog)94439444# need to wait for a heartbeat to arrive as then mavutil will9445# select the correct set of messages for us to receive in9446# self.mav.messages. You can actually receive messages with9447# recv_match and those will not be in self.mav.messages until9448# you do this!9449self.wait_heartbeat()9450self.get_autopilot_firmware_version()9451self.progress("Sim time: %f" % (self.get_sim_time(),))9452self.apply_default_parameters()94539454if not self.sitl_is_running():9455# we run this just to make sure exceptions are likely to9456# work OK.9457raise NotAchievedException("SITL is not running")9458self.progress("SITL is running")94599460self.progress("Ready to start testing!")94619462def upload_using_mission_protocol(self, mission_type, items):9463'''mavlink2 required'''9464target_system = 19465target_component = 19466self.do_timesync_roundtrip()9467tstart = self.get_sim_time()9468self.mav.mav.mission_count_send(target_system,9469target_component,9470len(items),9471mission_type)9472remaining_to_send = set(range(0, len(items)))9473sent = set()9474timeout = (10 + len(items)/10.0)9475while True:9476if self.get_sim_time_cached() - tstart > timeout:9477raise NotAchievedException("timeout uploading %s" % str(mission_type))9478if len(remaining_to_send) == 0:9479self.progress("All sent")9480break9481m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],9482blocking=True,9483timeout=1)9484if m is None:9485continue94869487if m.get_type() == 'MISSION_ACK':9488if (m.target_system == 255 and9489m.target_component == 0 and9490m.type == 1 and9491m.mission_type == 0):9492# this is just MAVProxy trying to screw us up9493continue9494raise NotAchievedException(f"Received unexpected mission ack {self.dump_message_verbose(m)}")94959496self.progress("Handling request for item %u/%u" % (m.seq, len(items)-1))9497self.progress("Item (%s)" % str(items[m.seq]))9498if m.seq in sent:9499self.progress("received duplicate request for item %u" % m.seq)9500continue95019502if m.seq not in remaining_to_send:9503raise NotAchievedException("received request for unknown item %u" % m.seq)95049505if m.mission_type != mission_type:9506raise NotAchievedException("received request for item from wrong mission type")95079508if items[m.seq].mission_type != mission_type:9509raise NotAchievedException(f"supplied item not of correct mission type (want={mission_type} got={items[m.seq].mission_type}") # noqa:5019510if items[m.seq].target_system != target_system:9511raise NotAchievedException("supplied item not of correct target system")9512if items[m.seq].target_component != target_component:9513raise NotAchievedException("supplied item not of correct target component")9514if items[m.seq].seq != m.seq:9515raise NotAchievedException("supplied item has incorrect sequence number (%u vs %u)" %9516(items[m.seq].seq, m.seq))95179518items[m.seq].pack(self.mav.mav)9519self.mav.mav.send(items[m.seq])9520remaining_to_send.discard(m.seq)9521sent.add(m.seq)95229523timeout += 10 # we received a good request for item; be generous with our timeouts95249525m = self.assert_receive_message('MISSION_ACK')9526if m.mission_type != mission_type:9527raise NotAchievedException("Mission ack not of expected mission type")9528if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:9529raise NotAchievedException("Mission upload failed (%s)" %9530(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),)9531self.progress("Upload of all %u items succeeded" % len(items))95329533def assert_fetch_mission_item_int(self, target_system, target_component, seq, mission_type):9534self.mav.mav.mission_request_int_send(target_system,9535target_component,9536seq,9537mission_type)9538m = self.assert_receive_message(9539'MISSION_ITEM_INT',9540condition=f'MISSION_ITEM_INT.mission_type=={mission_type}',9541)9542if m is None:9543raise NotAchievedException("Did not receive MISSION_ITEM_INT")9544return m95459546def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10):9547'''mavlink2 required'''9548target_system = 19549target_component = 19550self.progress("Sending mission_request_list")9551tstart = self.get_sim_time()9552self.mav.mav.mission_request_list_send(target_system,9553target_component,9554mission_type)95559556while True:9557if self.get_sim_time_cached() - tstart > timeout:9558raise NotAchievedException("Did not get MISSION_COUNT packet")9559m = self.mav.recv_match(blocking=True, timeout=0.1)9560if m is None:9561raise NotAchievedException("Did not get MISSION_COUNT response")9562if verbose:9563self.progress(str(m))9564if m.get_type() == 'MISSION_ACK':9565if m.target_system == 255 and m.target_component == 0:9566# this was for MAVProxy9567continue9568self.progress(self.dump_message_verbose(m))9569raise NotAchievedException("Received MISSION_ACK while waiting for MISSION_COUNT")9570if m.get_type() != 'MISSION_COUNT':9571continue9572if m.target_component != self.mav.source_system:9573continue9574if m.mission_type != mission_type:9575raise NotAchievedException("Mission count response of incorrect type")9576break95779578items = []9579tstart = self.get_sim_time_cached()9580remaining_to_receive = set(range(0, m.count))9581next_to_request = 09582timeout = m.count9583timeout *= self.speedup / 10.09584timeout += 109585while True:9586delta_t = self.get_sim_time_cached() - tstart9587if delta_t > timeout:9588raise NotAchievedException(9589"timeout downloading type=%s after %s seconds of %s allowed" %9590(mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name,9591delta_t, timeout))9592if len(remaining_to_receive) == 0:9593self.progress("All received")9594return items9595self.progress("Requesting item %u (remaining=%u)" %9596(next_to_request, len(remaining_to_receive)))9597m = self.assert_fetch_mission_item_int(target_system, target_component, next_to_request, mission_type)9598if m.target_system != self.mav.source_system:9599raise NotAchievedException("Wrong target system (want=%u got=%u)" %9600(self.mav.source_system, m.target_system))9601if m.target_component != self.mav.source_component:9602raise NotAchievedException("Wrong target component")9603self.progress("Got (%s)" % str(m))9604if m.mission_type != mission_type:9605raise NotAchievedException("Received waypoint of wrong type")9606if m.seq != next_to_request:9607raise NotAchievedException("Received waypoint is out of sequence")9608self.progress("Item %u OK" % m.seq)9609timeout += 10 # we received an item; be generous with our timeouts9610items.append(m)9611next_to_request += 19612remaining_to_receive.discard(m.seq)96139614def dump_message_verbose(self, m):9615'''return verbose dump of m. Wraps the pymavlink routine which9616inconveniently takes a filehandle'''9617f = io.StringIO()9618mavutil.dump_message_verbose(f, m)9619return f.getvalue()96209621def poll_home_position(self, quiet=True, timeout=30):9622old = self.mav.messages.get("HOME_POSITION", None)9623tstart = self.get_sim_time()9624while True:9625if self.get_sim_time_cached() - tstart > timeout:9626raise NotAchievedException("Failed to poll home position")9627if not quiet:9628self.progress("Sending MAV_CMD_GET_HOME_POSITION")9629try:9630self.run_cmd(9631mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,9632quiet=quiet,9633)9634except ValueError:9635continue9636m = self.mav.messages.get("HOME_POSITION", None)9637if m is None:9638continue9639if old is None:9640break9641if m._timestamp != old._timestamp:9642break9643self.progress("Polled home position (%s)" % str(m))9644return m96459646def position_target_loc(self):9647'''returns target location based on POSITION_TARGET_GLOBAL_INT'''9648m = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)9649return mavutil.location(m.lat_int*1e-7, m.lon_int*1e-7, m.alt)96509651def current_waypoint(self):9652m = self.assert_receive_message('MISSION_CURRENT')9653return m.seq96549655def distance_to_nav_target(self, use_cached_nav_controller_output=False):9656'''returns distance to waypoint navigation target in metres'''9657m = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None)9658if m is None or not use_cached_nav_controller_output:9659m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=10)9660return m.wp_dist96619662def distance_to_home(self, use_cached_home=False):9663m = self.mav.messages.get("HOME_POSITION", None)9664if use_cached_home is False or m is None:9665m = self.poll_home_position(quiet=True)9666here = self.assert_receive_message('GLOBAL_POSITION_INT')9667return self.get_distance_int(m, here)96689669def home_position_as_mav_location(self):9670m = self.poll_home_position()9671return mavutil.location(m.latitude*1.0e-7, m.longitude*1.0e-7, m.altitude*1.0e-3, 0)96729673def offset_location_ne(self, location, metres_north, metres_east):9674'''return a new location offset from passed-in location'''9675(target_lat, target_lng) = mavextra.gps_offset(location.lat,9676location.lng,9677metres_east,9678metres_north)9679return mavutil.location(target_lat,9680target_lng,9681location.alt,9682location.heading)96839684def offset_location_heading_distance(self, location, bearing, distance):9685(target_lat, target_lng) = mavextra.gps_newpos(9686location.lat,9687location.lng,9688bearing,9689distance9690)9691return mavutil.location(9692target_lat,9693target_lng,9694location.alt,9695location.heading9696)96979698def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):9699tstart = self.get_sim_time()9700while True:9701if self.get_sim_time_cached() - tstart > timeout:9702break9703m = self.assert_receive_message('VFR_HUD', timeout=timeout)9704if m.groundspeed > want+tolerance:9705raise NotAchievedException("Too fast (%f > %f)" %9706(m.groundspeed, want))9707if m.groundspeed < want-tolerance:9708raise NotAchievedException("Too slow (%f < %f)" %9709(m.groundspeed, want))9710self.progress("GroundSpeed OK (got=%f) (want=%f)" %9711(m.groundspeed, want))97129713def set_home(self, loc):9714'''set home to supplied loc'''9715self.run_cmd_int(9716mavutil.mavlink.MAV_CMD_DO_SET_HOME,9717p5=int(loc.lat*1e7),9718p6=int(loc.lng*1e7),9719p7=loc.alt,9720)97219722def SetHome(self):9723'''Setting and fetching of home'''9724if self.is_tracker():9725# tracker starts armed...9726self.disarm_vehicle(force=True)9727self.reboot_sitl()97289729# HOME_POSITION is used as a surrogate for origin until we9730# start emitting GPS_GLOBAL_ORIGIN9731self.wait_ekf_happy()9732orig_home = self.poll_home_position()9733if orig_home is None:9734raise AutoTestTimeoutException()9735self.progress("Original home: %s" % str(orig_home))9736# original home should be close to SITL home...9737start_loc = self.sitl_start_location()9738self.progress("SITL start loc: %s" % str(start_loc))9739delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)9740if delta > 0.000006:9741raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %9742(orig_home.latitude * 1.0e-7, start_loc.lat, delta))9743delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)9744if delta > 0.000006:9745raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %9746(orig_home.longitude * 1.0e-7, start_loc.lng, delta))9747if self.is_rover():9748self.progress("### Rover skipping altitude check unti position fixes in")9749else:9750home_alt_m = orig_home.altitude * 1.0e-39751if abs(home_alt_m - start_loc.alt) > 2: # metres9752raise ValueError("homes differ in alt got=%fm want=%fm" %9753(home_alt_m, start_loc.alt))9754new_x = orig_home.latitude + 10009755new_y = orig_home.longitude + 20009756new_z = orig_home.altitude + 300000 # 300 metres9757print("new home: %s %s %s" % (str(new_x), str(new_y), str(new_z)))9758self.run_cmd_int(9759mavutil.mavlink.MAV_CMD_DO_SET_HOME,9760p5=new_x,9761p6=new_y,9762p7=new_z/1000.0, # mm => m9763)97649765home = self.poll_home_position()9766self.progress("home: %s" % str(home))9767got_home_latitude = home.latitude9768got_home_longitude = home.longitude9769got_home_altitude = home.altitude9770if (got_home_latitude != new_x or9771got_home_longitude != new_y or9772abs(got_home_altitude - new_z) > 100): # float-conversion issues9773self.reboot_sitl()9774raise NotAchievedException(9775"Home mismatch got=(%f, %f, %f) set=(%f, %f, %f)" %9776(got_home_latitude, got_home_longitude, got_home_altitude,9777new_x, new_y, new_z))97789779self.progress("monitoring home to ensure it doesn't drift at all")9780tstart = self.get_sim_time()9781while self.get_sim_time_cached() - tstart < 10:9782home = self.poll_home_position(quiet=True)9783self.progress("home: %s" % str(home))9784if (home.latitude != got_home_latitude or9785home.longitude != got_home_longitude or9786home.altitude != got_home_altitude): # float-conversion issues9787self.reboot_sitl()9788raise NotAchievedException("home is drifting")97899790self.progress("Waiting for EKF to start")9791self.wait_ready_to_arm()9792self.progress("now use lat=0, lon=0 to reset home to current location")9793self.run_cmd_int(9794mavutil.mavlink.MAV_CMD_DO_SET_HOME,9795p5=0, # lat9796p6=0, # lon9797p7=new_z/1000.0, # mm => m9798)9799home = self.poll_home_position()9800self.progress("home: %s" % str(home))9801if self.distance_to_home(use_cached_home=True) > 1:9802raise NotAchievedException("Setting home to current location did not work")98039804self.progress("Setting home elsewhere again")9805self.run_cmd_int(9806mavutil.mavlink.MAV_CMD_DO_SET_HOME,9807p5=new_x,9808p6=new_y,9809p7=new_z/1000.0, # mm => m9810)9811if self.distance_to_home() < 10:9812raise NotAchievedException("Setting home to location did not work")98139814self.progress("use param1=1 to reset home to current location")9815self.run_cmd_int(9816mavutil.mavlink.MAV_CMD_DO_SET_HOME,9817p1=1, # use current location9818p5=37, # lat9819p6=21, # lon9820p7=new_z/1000.0, # mm => m9821)9822home = self.poll_home_position()9823self.progress("home: %s" % str(home))9824if self.distance_to_home() > 1:9825raise NotAchievedException("Setting home to current location did not work")98269827if self.is_tracker():9828# tracker starts armed...9829self.disarm_vehicle(force=True)9830self.reboot_sitl()98319832def zero_mag_offset_parameters(self, compass_count=3):9833self.progress("Zeroing Mag OFS parameters")9834self.get_sim_time()9835zero_offset_parameters_hash = {}9836for num in "", "2", "3":9837for axis in "X", "Y", "Z":9838name = "COMPASS_OFS%s_%s" % (num, axis)9839zero_offset_parameters_hash[name] = 09840self.set_parameters(zero_offset_parameters_hash)9841# force-save the calibration values:9842self.run_cmd_int(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, p2=76)9843self.progress("zeroed mag parameters")98449845params = [9846[("SIM_MAG1_OFS1_X", "COMPASS_OFS_X", 0),9847("SIM_MAG1_OFS1_Y", "COMPASS_OFS_Y", 0),9848("SIM_MAG1_OFS1_Z", "COMPASS_OFS_Z", 0), ],9849]9850for count in range(2, compass_count + 1):9851params += [9852[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, 0),9853("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, 0),9854("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, 0), ],9855]9856self.check_zero_mag_parameters(params)98579858def forty_two_mag_dia_odi_parameters(self, compass_count=3):9859self.progress("Forty twoing Mag DIA and ODI parameters")9860self.get_sim_time()9861params = [9862[("SIM_MAG1_DIA_X", "COMPASS_DIA_X", 42.0),9863("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", 42.0),9864("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", 42.0),9865("SIM_MAG1_ODI_X", "COMPASS_ODI_X", 42.0),9866("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", 42.0),9867("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", 42.0), ],9868]9869for count in range(2, compass_count + 1):9870params += [9871[("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, 42.0),9872("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, 42.0),9873("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, 42.0),9874("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, 42.0),9875("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, 42.0),9876("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, 42.0), ],9877]9878self.wait_heartbeat()9879to_set = {}9880for param_set in params:9881for param in param_set:9882(_, _out, value) = param9883to_set[_out] = value9884self.set_parameters(to_set)9885self.check_zero_mag_parameters(params)98869887def check_mag_parameters(self, parameter_stuff, compass_number):9888self.progress("Checking that Mag parameter")9889for idx in range(0, compass_number, 1):9890for param in parameter_stuff[idx]:9891(_in, _out, value) = param9892got_value = self.get_parameter(_out)9893if abs(got_value - value) > abs(value) * 0.15:9894raise NotAchievedException("%s/%s not within 15%%; got %f want=%f" % (_in, _out, got_value, value))98959896def check_zero_mag_parameters(self, parameter_stuff):9897self.progress("Checking that Mag OFS are zero")9898for param_set in parameter_stuff:9899for param in param_set:9900(_in, _out, _) = param9901got_value = self.get_parameter(_out)9902max = 0.159903if "DIA" in _out or "ODI" in _out:9904max += 42.09905if abs(got_value) > max:9906raise NotAchievedException(9907"%s/%s not within 15%%; got %f want=%f" %9908(_in, _out, got_value, 0.0 if max > 1 else 42.0))99099910def check_zeros_mag_orient(self, compass_count=3):9911self.progress("zeroed mag parameters")9912self.verify_parameter_values({"COMPASS_ORIENT": 0})9913for count in range(2, compass_count + 1):9914self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0})99159916# this autotest appears to interfere with FixedYawCalibration, no idea why.9917def SITLCompassCalibration(self, compass_count=3, timeout=1000):9918'''Test Fixed Yaw Calibration"'''99199920timeout /= 89921timeout *= self.speedup99229923def reset_pos_and_start_magcal(mavproxy, tmask):9924mavproxy.send("sitl_stop\n")9925mavproxy.send("sitl_attitude 0 0 0\n")9926self.get_sim_time()9927self.run_cmd(9928mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,9929p1=tmask, # p1: mag_mask9930p2=0, # retry9931p3=0, # autosave9932p4=0, # delay9933want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,9934timeout=20,9935)9936mavproxy.send("sitl_magcal\n")99379938def do_prep_mag_cal_test(mavproxy, params):9939self.progress("Preparing the vehicle for magcal")9940MAG_OFS = 1009941MAG_DIA = 1.09942MAG_ODI = 0.0049943params += [9944[("SIM_MAG1_OFS_X", "COMPASS_OFS_X", MAG_OFS),9945("SIM_MAG1_OFS_Y", "COMPASS_OFS_Y", MAG_OFS + 100),9946("SIM_MAG1_OFS_Z", "COMPASS_OFS_Z", MAG_OFS + 200),9947("SIM_MAG1_DIA_X", "COMPASS_DIA_X", MAG_DIA),9948("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", MAG_DIA + 0.1),9949("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", MAG_DIA + 0.2),9950("SIM_MAG1_ODI_X", "COMPASS_ODI_X", MAG_ODI),9951("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", MAG_ODI + 0.001),9952("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", MAG_ODI + 0.001), ],9953]9954for count in range(2, compass_count + 1):9955params += [9956[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),9957("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),9958("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),9959("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),9960("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),9961("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),9962("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),9963("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),9964("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],9965]9966self.progress("Setting calibration mode")9967self.wait_heartbeat()9968self.customise_SITL_commandline(["-M", "calibration"])9969self.mavproxy_load_module(mavproxy, "sitl_calibration")9970self.mavproxy_load_module(mavproxy, "calibration")9971self.mavproxy_load_module(mavproxy, "relay")9972self.wait_statustext("is using GPS", timeout=60)9973mavproxy.send("accelcalsimple\n")9974mavproxy.expect("Calibrated")9975# disable it to not interfert with calibration acceptation9976self.mavproxy_unload_module(mavproxy, "calibration")9977if self.is_copter():9978# set frame class to pass arming check on copter9979self.set_parameter("FRAME_CLASS", 1)9980self.progress("Setting SITL Magnetometer model value")9981self.set_parameter("COMPASS_AUTO_ROT", 0)9982# MAG_ORIENT = 49983# self.set_parameter("SIM_MAG1_ORIENT", MAG_ORIENT)9984# for count in range(2, compass_count + 1):9985# self.set_parameter("SIM_MAG%d_ORIENT" % count, MAG_ORIENT * (count % 41))9986# # set compass external to check that orientation is found and auto set9987# self.set_parameter("COMPASS_EXTERN%d" % count, 1)9988to_set = {}9989for param_set in params:9990for param in param_set:9991(_in, _out, value) = param9992to_set[_in] = value9993to_set[_out] = value9994self.set_parameters(to_set)9995self.start_subtest("Zeroing Mag OFS parameters with Mavlink")9996self.zero_mag_offset_parameters()9997self.progress("=========================================")9998# Change the default value to unexpected 429999self.forty_two_mag_dia_odi_parameters()10000self.progress("Zeroing Mags orientations")10001self.set_parameter("COMPASS_ORIENT", 0)10002for count in range(2, compass_count + 1):10003self.set_parameter("COMPASS_ORIENT%d" % count, 0)1000410005# Only care about compass prearm10006self.set_parameter("ARMING_SKIPCHK", ~(1 << 2))1000710008#################################################10009def do_test_mag_cal(mavproxy, params, compass_tnumber):10010self.start_subtest("Try magcal and make it stop around 30%")10011self.progress("Compass mask is %s" % "{0:b}".format(target_mask))10012reset_pos_and_start_magcal(mavproxy, target_mask)10013tstart = self.get_sim_time()10014reached_pct = [0] * compass_tnumber10015tstop = None10016while True:10017if self.get_sim_time_cached() - tstart > timeout:10018raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")10019m = self.mav.recv_match(type='MAG_CAL_PROGRESS', blocking=True, timeout=5)10020if m is None:10021if tstop is not None:10022# wait 3 second to unsure that the calibration is well stopped10023if self.get_sim_time_cached() - tstop > 10:10024if reached_pct[0] > 33:10025raise NotAchievedException("Mag calibration didn't stop")10026else:10027break10028else:10029continue10030else:10031continue10032if m is not None:10033self.progress("Mag CAL progress: %s" % str(m))10034cid = m.compass_id10035new_pct = int(m.completion_pct)10036if new_pct != reached_pct[cid]:10037if new_pct < reached_pct[cid]:10038raise NotAchievedException("Mag calibration restart when it shouldn't")10039reached_pct[cid] = new_pct10040self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))10041if cid == 0 and 13 <= reached_pct[0] <= 15:10042self.progress("Request again to start calibration, it shouldn't restart from 0")10043self.run_cmd(10044mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,10045p1=target_mask,10046want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,10047timeout=20,10048)1004910050if reached_pct[0] > 30:10051self.run_cmd(10052mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,10053p1=target_mask,10054want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,10055)10056if tstop is None:10057tstop = self.get_sim_time_cached()10058if tstop is not None:10059# wait 3 second to unsure that the calibration is well stopped10060if self.get_sim_time_cached() - tstop > 3:10061raise NotAchievedException("Mag calibration didn't stop")10062self.check_zero_mag_parameters(params)10063self.check_zeros_mag_orient()1006410065#################################################10066self.start_subtest("Try magcal and make it failed")10067self.progress("Compass mask is %s" % "{0:b}".format(target_mask))10068old_cal_fit = self.get_parameter("COMPASS_CAL_FIT")10069self.set_parameter("COMPASS_CAL_FIT", 0.001, add_to_context=False)10070reset_pos_and_start_magcal(mavproxy, target_mask)10071tstart = self.get_sim_time()10072reached_pct = [0] * compass_tnumber10073report_get = [0] * compass_tnumber10074while True:10075if self.get_sim_time_cached() - tstart > timeout:10076raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")10077m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=10)10078if m.get_type() == "MAG_CAL_REPORT":10079if report_get[m.compass_id] == 0:10080self.progress("Report: %s" % str(m))10081if m.cal_status == mavutil.mavlink.MAG_CAL_FAILED:10082report_get[m.compass_id] = 110083else:10084raise NotAchievedException("Mag calibration didn't failed")10085if all(ele >= 1 for ele in report_get):10086self.progress("All Mag report failure")10087break10088if m is not None and m.get_type() == "MAG_CAL_PROGRESS":10089self.progress("Mag CAL progress: %s" % str(m))10090cid = m.compass_id10091new_pct = int(m.completion_pct)10092if new_pct != reached_pct[cid]:10093reached_pct[cid] = new_pct10094self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))10095if cid == 0 and 49 <= reached_pct[0] <= 50:10096self.progress("Try arming during calibration, should failed")10097self.try_arm(False, "Compass calibration running")1009810099self.check_zero_mag_parameters(params)10100self.check_zeros_mag_orient()10101self.set_parameter("COMPASS_CAL_FIT", old_cal_fit, add_to_context=False)1010210103#################################################10104self.start_subtest("Try magcal and wait success")10105self.progress("Compass mask is %s" % "{0:b}".format(target_mask))10106reset_pos_and_start_magcal(mavproxy, target_mask)10107progress_count = [0] * compass_tnumber10108reached_pct = [0] * compass_tnumber10109report_get = [0] * compass_tnumber10110tstart = self.get_sim_time()10111while True:10112if self.get_sim_time_cached() - tstart > timeout:10113raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")10114m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=5)10115if m.get_type() == "MAG_CAL_REPORT":10116if report_get[m.compass_id] == 0:10117self.progress("Report: %s" % self.dump_message_verbose(m))10118param_names = ["SIM_MAG1_ORIENT"]10119for i in range(2, compass_tnumber+1):10120param_names.append("SIM_MAG%u_ORIENT" % i)10121for param_name in param_names:10122self.progress("%s=%f" % (param_name, self.get_parameter(param_name)))10123if m.cal_status == mavutil.mavlink.MAG_CAL_SUCCESS:10124threshold = 9510125if reached_pct[m.compass_id] < threshold:10126raise NotAchievedException(10127"Mag calibration report SUCCESS without >=%f%% completion (got %f%%)" %10128(threshold, reached_pct[m.compass_id]))10129report_get[m.compass_id] = 110130else:10131raise NotAchievedException(10132"Mag calibration didn't SUCCEED (cal_status=%u) (progress_count=%s)" %10133(m.cal_status, progress_count[m.compass_id],))10134if all(ele >= 1 for ele in report_get):10135self.progress("All Mag report SUCCESS")10136break10137if m is not None and m.get_type() == "MAG_CAL_PROGRESS":10138cid = m.compass_id10139new_pct = int(m.completion_pct)10140progress_count[cid] += 110141if new_pct != reached_pct[cid]:10142reached_pct[cid] = new_pct10143self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))10144mavproxy.send("sitl_stop\n")10145mavproxy.send("sitl_attitude 0 0 0\n")10146self.progress("Checking that value aren't changed without acceptation")10147self.check_zero_mag_parameters(params)10148self.check_zeros_mag_orient()10149self.progress("Send acceptation and check value")10150self.wait_heartbeat()10151self.run_cmd(10152mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,10153p1=target_mask, # p1: mag_mask10154want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,10155timeout=20,10156)10157self.check_mag_parameters(params, compass_tnumber)10158self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG1_ORIENT")})10159for count in range(2, compass_tnumber + 1):10160self.verify_parameter_values({"COMPASS_ORIENT%d" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})10161self.try_arm(False, "Compass calibrated requires reboot")1016210163# test buzzer/notify ?10164self.progress("Rebooting and making sure we could arm with these values")10165self.drain_mav()10166self.reboot_sitl()10167if False: # FIXME! This fails with compasses inconsistent!10168self.wait_ready_to_arm(timeout=60)10169self.progress("Setting manually the parameter for other sensor to avoid compass consistency error")10170for idx in range(compass_tnumber, compass_count, 1):10171for param in params[idx]:10172(_in, _out, value) = param10173self.set_parameter(_out, value)10174for count in range(compass_tnumber + 1, compass_count + 1):10175self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))10176self.arm_vehicle()10177self.progress("Test calibration rejection when armed")10178self.run_cmd(10179mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,10180p1=target_mask, # p1: mag_mask10181p2=0, # retry10182p3=0, # autosave10183p4=0, # delay10184want_result=mavutil.mavlink.MAV_RESULT_FAILED,10185timeout=20,10186)10187self.disarm_vehicle()10188self.mavproxy_unload_module(mavproxy, "relay")10189self.mavproxy_unload_module(mavproxy, "sitl_calibration")1019010191ex = None1019210193mavproxy = self.start_mavproxy()10194try:10195self.set_parameter("AHRS_EKF_TYPE", 10)10196self.set_parameter("SIM_GND_BEHAV", 0)1019710198curr_params = []10199target_mask = 010200# we test all bitmask plus 0 for all10201for run in range(-1, compass_count, 1):10202ntest_compass = compass_count10203if run < 0:10204# use bitmask 0 for all compass10205target_mask = 010206else:10207target_mask |= (1 << run)10208ntest_compass = run + 110209do_prep_mag_cal_test(mavproxy, curr_params)10210do_test_mag_cal(mavproxy, curr_params, ntest_compass)1021110212except Exception as e:10213self.progress("Caught exception: %s" %10214self.get_exception_stacktrace(e))10215ex = e10216self.mavproxy_unload_module(mavproxy, "relay")10217self.mavproxy_unload_module(mavproxy, "sitl_calibration")10218if ex is not None:10219raise ex1022010221self.stop_mavproxy(mavproxy)1022210223# need to reboot SITL after moving away from EKF type 10; we10224# can end up with home set but origin not and that will lead10225# to bad things.10226self.reboot_sitl()1022710228def test_mag_reordering_assert_mag_transform(self, values, transforms):10229'''transforms ought to be read as, "take all the parameter values from10230the first compass parameters and shove them into the second indicating10231compass parameters'''1023210233# create a set of mappings from one parameter name to another10234# e.g. COMPASS_OFS_X => COMPASS_OFS2_X if the transform is10235# [(1,2)]. [(1,2),(2,1)] should swap the compass values1023610237parameter_mappings = {}10238for key in values.keys():10239parameter_mappings[key] = key10240for (old_compass_num, new_compass_num) in transforms:10241old_key_compass_bit = str(old_compass_num)10242if old_key_compass_bit == "1":10243old_key_compass_bit = ""10244new_key_compass_bit = str(new_compass_num)10245if new_key_compass_bit == "1":10246new_key_compass_bit = ""10247# vectors first:10248for key_vector_bit in ["OFS", "DIA", "ODI", "MOT"]:10249for axis in "X", "Y", "Z":10250old_key = "COMPASS_%s%s_%s" % (key_vector_bit,10251old_key_compass_bit,10252axis)10253new_key = "COMPASS_%s%s_%s" % (key_vector_bit,10254new_key_compass_bit,10255axis)10256parameter_mappings[old_key] = new_key10257# then non-vectorey bits:10258for key_bit in "SCALE", "ORIENT":10259old_key = "COMPASS_%s%s" % (key_bit, old_key_compass_bit)10260new_key = "COMPASS_%s%s" % (key_bit, new_key_compass_bit)10261parameter_mappings[old_key] = new_key10262# then a sore thumb:10263if old_key_compass_bit == "":10264old_key = "COMPASS_EXTERNAL"10265else:10266old_key = "COMPASS_EXTERN%s" % old_key_compass_bit10267if new_key_compass_bit == "":10268new_key = "COMPASS_EXTERNAL"10269else:10270new_key = "COMPASS_EXTERN%s" % new_key_compass_bit10271parameter_mappings[old_key] = new_key1027210273for key in values.keys():10274newkey = parameter_mappings[key]10275current_value = self.get_parameter(newkey)10276expected_value = values[key]10277if abs(current_value - expected_value) > 0.001:10278raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" %10279(newkey, expected_value, current_value, str(transforms), key))1028010281def CompassReordering(self):10282'''Test Compass reordering when priorities are changed'''10283originals = {10284"COMPASS_OFS_X": 1.1,10285"COMPASS_OFS_Y": 1.2,10286"COMPASS_OFS_Z": 1.3,10287"COMPASS_DIA_X": 1.4,10288"COMPASS_DIA_Y": 1.5,10289"COMPASS_DIA_Z": 1.6,10290"COMPASS_ODI_X": 1.7,10291"COMPASS_ODI_Y": 1.8,10292"COMPASS_ODI_Z": 1.9,10293"COMPASS_MOT_X": 1.91,10294"COMPASS_MOT_Y": 1.92,10295"COMPASS_MOT_Z": 1.93,10296"COMPASS_SCALE": 1.94,10297"COMPASS_ORIENT": 1,10298"COMPASS_EXTERNAL": 2,1029910300"COMPASS_OFS2_X": 2.1,10301"COMPASS_OFS2_Y": 2.2,10302"COMPASS_OFS2_Z": 2.3,10303"COMPASS_DIA2_X": 2.4,10304"COMPASS_DIA2_Y": 2.5,10305"COMPASS_DIA2_Z": 2.6,10306"COMPASS_ODI2_X": 2.7,10307"COMPASS_ODI2_Y": 2.8,10308"COMPASS_ODI2_Z": 2.9,10309"COMPASS_MOT2_X": 2.91,10310"COMPASS_MOT2_Y": 2.92,10311"COMPASS_MOT2_Z": 2.93,10312"COMPASS_SCALE2": 2.94,10313"COMPASS_ORIENT2": 3,10314"COMPASS_EXTERN2": 4,1031510316"COMPASS_OFS3_X": 3.1,10317"COMPASS_OFS3_Y": 3.2,10318"COMPASS_OFS3_Z": 3.3,10319"COMPASS_DIA3_X": 3.4,10320"COMPASS_DIA3_Y": 3.5,10321"COMPASS_DIA3_Z": 3.6,10322"COMPASS_ODI3_X": 3.7,10323"COMPASS_ODI3_Y": 3.8,10324"COMPASS_ODI3_Z": 3.9,10325"COMPASS_MOT3_X": 3.91,10326"COMPASS_MOT3_Y": 3.92,10327"COMPASS_MOT3_Z": 3.93,10328"COMPASS_SCALE3": 3.94,10329"COMPASS_ORIENT3": 5,10330"COMPASS_EXTERN3": 6,10331}1033210333# quick sanity check to ensure all values are unique:10334if len(originals.values()) != len(set(originals.values())):10335raise NotAchievedException("Values are not all unique!")1033610337self.progress("Setting parameters")10338self.set_parameters(originals)1033910340self.reboot_sitl()1034110342# no transforms means our originals should be our finals:10343self.test_mag_reordering_assert_mag_transform(originals, [])1034410345self.start_subtest("Pushing 1st mag to 3rd")10346self.context_push()10347# now try reprioritising compass 1 to be higher than compass 0:10348prio1_id = self.get_parameter("COMPASS_PRIO1_ID")10349prio2_id = self.get_parameter("COMPASS_PRIO2_ID")10350prio3_id = self.get_parameter("COMPASS_PRIO3_ID")10351self.set_parameters({10352"COMPASS_PRIO1_ID": prio2_id,10353"COMPASS_PRIO2_ID": prio3_id,10354"COMPASS_PRIO3_ID": prio1_id,10355})1035610357self.reboot_sitl()1035810359self.test_mag_reordering_assert_mag_transform(originals, [10360(2, 1),10361(3, 2),10362(1, 3),10363])1036410365self.progress("Setting priorities back to original order")10366self.set_parameters({10367"COMPASS_PRIO1_ID": prio1_id,10368"COMPASS_PRIO2_ID": prio2_id,10369"COMPASS_PRIO3_ID": prio3_id,10370})1037110372self.reboot_sitl()1037310374self.test_mag_reordering_assert_mag_transform(originals, [10375(1, 1),10376(2, 2),10377(3, 3),10378])1037910380self.progress("And reverse ordering")10381self.set_parameters({10382"COMPASS_PRIO1_ID": prio3_id,10383"COMPASS_PRIO2_ID": prio2_id,10384"COMPASS_PRIO3_ID": prio1_id,10385})1038610387self.reboot_sitl()1038810389self.test_mag_reordering_assert_mag_transform(originals, [10390(1, 3),10391(2, 2),10392(3, 1),10393])1039410395self.context_pop()1039610397def SixCompassCalibrationAndReordering(self):10398'''Test reordering of 6 simulated compasses by changing priority and appearance order'''10399self.context_push()1040010401total_compasses = 61040210403self.progress("Setting up 6 simulated I2C compasses with calibration")1040410405# Fetch existing SIM_MAGx_DEVID values10406device_ids = self.get_sim_mag_devids(total_compasses)1040710408# disable force saving dev_ids for subsequent boots10409self.set_parameter("SIM_MAG_SAVE_IDS", 0)1041010411self.reboot_sitl()10412self.wait_ready_to_arm()1041310414# Verify all 6 compasses are detected (stored in DEV_ID parameters)10415self.progress("Verifying 6 compasses detected in DEV_ID slots")10416self.check_mag_devids_detected(total_compasses)1041710418# Reboot to apply changes10419self.progress("Rebooting to apply reordering")10420self.reboot_sitl()1042110422def wait_correct_compass_prearm_message():10423# Check for correct compass prearm messages10424# We expect "PreArm: Compass not calibrated" but NOT10425# "PreArm: Compass x not found" or any other compass prearm message10426self.progress("Waiting for compass prearm message")10427self.context_collect("STATUSTEXT")10428msg = self.wait_statustext("PreArm: Compass", timeout=60, check_context=True)1042910430# Check if we got the expected message or an unexpected one10431if "not found" in msg.text.lower():10432self.context_clear_collection("STATUSTEXT")10433raise NotAchievedException(f"Unexpected compass not found: {msg.text}")10434elif "not calibrated" in msg.text.lower():10435self.progress(f"Got expected prearm failure: {msg.text}")10436else:10437self.context_clear_collection("STATUSTEXT")10438raise NotAchievedException(f"Unexpected compass prearm message: {msg.text}")1043910440self.context_clear_collection("STATUSTEXT")1044110442# Change appearance order: swap positions 2 and 410443# Reorder: [dev1, dev4, dev3, dev2, dev5, dev6]10444reordered = [device_ids[0], device_ids[3], device_ids[2],10445device_ids[1], device_ids[4], device_ids[5]]10446self.reorder_compass_appearance(reordered)1044710448# Set priority for compass 410449self.set_parameter("COMPASS_PRIO3_ID", device_ids[3])1045010451self.reboot_sitl()10452wait_correct_compass_prearm_message()1045310454# Verify all 6 compasses are still present (in any DEV_ID slot)10455self.progress("Verifying all 6 compasses still present after reordering")10456self.check_mag_devids_detected(total_compasses)1045710458self.reorder_compass_appearance(reordered)10459self.progress("Setting priorities to use last three compasses")10460self.set_parameters({10461"COMPASS_PRIO1_ID": device_ids[3],10462"COMPASS_PRIO2_ID": device_ids[4],10463"COMPASS_PRIO3_ID": device_ids[5],10464})10465self.reboot_sitl()10466wait_correct_compass_prearm_message()10467self.check_mag_devids_detected(total_compasses)1046810469# revert to original10470self.progress("Reverting to original compass priorities")10471self.reorder_compass_appearance(device_ids)10472self.set_parameters({10473"COMPASS_PRIO1_ID": device_ids[0],10474"COMPASS_PRIO2_ID": device_ids[1],10475"COMPASS_PRIO3_ID": device_ids[2],10476})10477self.reboot_sitl()10478self.wait_ready_to_arm()1047910480self.progress("SixCompassCalibrationAndReordering completed successfully")10481self.context_pop()1048210483# something about SITLCompassCalibration appears to fail10484# this one, so we put it first:10485def FixedYawCalibration(self):10486'''Test Fixed Yaw Calibration'''10487self.context_push()10488ex = None10489try:10490MAG_OFS_X = 10010491MAG_OFS_Y = 20010492MAG_OFS_Z = 30010493wanted = {10494"COMPASS_OFS_X": (MAG_OFS_X, 3.0),10495"COMPASS_OFS_Y": (MAG_OFS_Y, 3.0),10496"COMPASS_OFS_Z": (MAG_OFS_Z, 3.0),10497"COMPASS_DIA_X": 1,10498"COMPASS_DIA_Y": 1,10499"COMPASS_DIA_Z": 1,10500"COMPASS_ODI_X": 0,10501"COMPASS_ODI_Y": 0,10502"COMPASS_ODI_Z": 0,1050310504"COMPASS_OFS2_X": (MAG_OFS_X, 3.0),10505"COMPASS_OFS2_Y": (MAG_OFS_Y, 3.0),10506"COMPASS_OFS2_Z": (MAG_OFS_Z, 3.0),10507"COMPASS_DIA2_X": 1,10508"COMPASS_DIA2_Y": 1,10509"COMPASS_DIA2_Z": 1,10510"COMPASS_ODI2_X": 0,10511"COMPASS_ODI2_Y": 0,10512"COMPASS_ODI2_Z": 0,1051310514"COMPASS_OFS3_X": (MAG_OFS_X, 3.0),10515"COMPASS_OFS3_Y": (MAG_OFS_Y, 3.0),10516"COMPASS_OFS3_Z": (MAG_OFS_Z, 3.0),10517"COMPASS_DIA3_X": 1,10518"COMPASS_DIA3_Y": 1,10519"COMPASS_DIA3_Z": 1,10520"COMPASS_ODI3_X": 0,10521"COMPASS_ODI3_Y": 0,10522"COMPASS_ODI3_Z": 0,10523}10524self.set_parameters({10525"SIM_MAG1_OFS_X": MAG_OFS_X,10526"SIM_MAG1_OFS_Y": MAG_OFS_Y,10527"SIM_MAG1_OFS_Z": MAG_OFS_Z,1052810529"SIM_MAG2_OFS_X": MAG_OFS_X,10530"SIM_MAG2_OFS_Y": MAG_OFS_Y,10531"SIM_MAG2_OFS_Z": MAG_OFS_Z,1053210533"SIM_MAG3_OFS_X": MAG_OFS_X,10534"SIM_MAG3_OFS_Y": MAG_OFS_Y,10535"SIM_MAG3_OFS_Z": MAG_OFS_Z,10536})1053710538# set to some sensible-ish initial values. If your initial10539# offsets are way, way off you can get some very odd effects.10540for param in wanted:10541value = 0.010542if "DIA" in param:10543value = 1.00110544elif "ODI" in param:10545value = 0.00110546self.set_parameter(param, value)1054710548self.zero_mag_offset_parameters()1054910550# wait until we definitely know where we are:10551self.poll_home_position(timeout=120)1055210553ss = self.assert_receive_message('SIMSTATE', verbose=True)1055410555self.run_cmd(10556mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,10557p1=math.degrees(ss.yaw),10558)10559self.verify_parameter_values(wanted)1056010561# run same command but as command_int:10562self.zero_mag_offset_parameters()10563self.run_cmd_int(10564mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,10565p1=math.degrees(ss.yaw),10566)10567self.verify_parameter_values(wanted)1056810569self.progress("Rebooting and making sure we could arm with these values")10570self.reboot_sitl()10571self.wait_ready_to_arm(timeout=60)1057210573except Exception as e:10574ex = e1057510576self.context_pop()1057710578if ex is not None:10579raise ex1058010581def DataFlashOverMAVLink(self):10582'''Test DataFlash over MAVLink'''10583self.context_push()10584ex = None10585mavproxy = self.start_mavproxy()10586try:10587self.set_parameter("LOG_BACKEND_TYPE", 2)10588self.reboot_sitl()10589self.wait_ready_to_arm(check_prearm_bit=False)10590mavproxy.send('arm throttle\n')10591mavproxy.expect('PreArm: Logging failed')10592self.mavproxy_load_module(mavproxy, 'dataflash_logger')10593mavproxy.send("dataflash_logger set verbose 1\n")10594mavproxy.expect('logging started')10595mavproxy.send("dataflash_logger set verbose 0\n")10596self.delay_sim_time(1)10597self.do_timesync_roundtrip() # drain COMMAND_ACK from that failed arm10598self.arm_vehicle()10599tstart = self.get_sim_time()10600last_status = 010601mavproxy.send('repeat add 1 dataflash_logger status\n')10602while True:10603now = self.get_sim_time()10604if now - tstart > 60:10605break10606if now - last_status > 5:10607last_status = now10608# seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:010609mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")10610rate = float(mavproxy.match.group(1))10611self.progress("Rate: %f" % rate)10612desired_rate = 5010613if self.valgrind or self.callgrind:10614desired_rate /= 1010615if rate < desired_rate:10616raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))10617self.disarm_vehicle()10618mavproxy.send('repeat remove 0\n')10619except Exception as e:10620self.print_exception_caught(e)10621self.disarm_vehicle()10622ex = e10623self.mavproxy_unload_module(mavproxy, 'dataflash_logger')1062410625# the following things won't work - but they shouldn't die either:10626self.mavproxy_load_module(mavproxy, 'log')1062710628self.progress("Try log list")10629mavproxy.send("log list\n")10630mavproxy.expect("No logs")1063110632self.progress("Try log erase")10633mavproxy.send("log erase\n")10634# no response to this...1063510636self.progress("Try log download")10637mavproxy.send("log download 1\n")10638# no response to this...1063910640self.mavproxy_unload_module(mavproxy, 'log')1064110642self.context_pop()1064310644self.stop_mavproxy(mavproxy)10645self.reboot_sitl()10646if ex is not None:10647raise ex1064810649def DataFlash(self):10650"""Test DataFlash SITL backend"""10651self.context_push()10652ex = None10653mavproxy = self.start_mavproxy()10654try:10655self.set_parameter("LOG_BACKEND_TYPE", 4)10656self.set_parameter("LOG_FILE_DSRMROT", 1)10657self.set_parameter("LOG_BLK_RATEMAX", 1)10658self.reboot_sitl()10659# First log created here, but we are in chip erase so ignored10660mavproxy.send("module load log\n")10661mavproxy.send("log erase\n")10662mavproxy.expect("Chip erase complete")1066310664self.wait_ready_to_arm()10665if self.is_copter() or self.is_plane():10666self.set_autodisarm_delay(0)10667self.arm_vehicle()10668self.delay_sim_time(5)10669self.disarm_vehicle()10670# First log created here10671self.delay_sim_time(2)10672self.arm_vehicle()10673self.delay_sim_time(5)10674self.disarm_vehicle()10675# Second log created here10676self.delay_sim_time(2)10677mavproxy.send("log list\n")10678mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)10679log_num = int(mavproxy.match.group(1))10680numlogs = int(mavproxy.match.group(2))10681lastlog = int(mavproxy.match.group(3))10682size = int(mavproxy.match.group(4))10683if numlogs != 2 or log_num != 1 or size <= 0:10684raise NotAchievedException("Unexpected log information %d %d %d" % (log_num, numlogs, lastlog))10685self.progress("Log size: %d" % size)10686self.reboot_sitl()10687# This starts a new log with a time of 0, wait for arm so that we can insert the correct time10688self.wait_ready_to_arm()10689# Third log created here10690mavproxy.send("log list\n")10691mavproxy.expect("Log 1 numLogs 3 lastLog 3 size")1069210693# Download second and third logs10694mavproxy.send("log download 2 logs/dataflash-log-002.BIN\n")10695mavproxy.expect("Finished downloading", timeout=120)10696mavproxy.send("log download 3 logs/dataflash-log-003.BIN\n")10697mavproxy.expect("Finished downloading", timeout=120)1069810699# Erase the logs10700mavproxy.send("log erase\n")10701mavproxy.expect("Chip erase complete")1070210703except Exception as e:10704self.print_exception_caught(e)10705ex = e10706mavproxy.send("module unload log\n")10707self.stop_mavproxy(mavproxy)10708self.context_pop()10709self.reboot_sitl()10710if ex is not None:10711raise ex1071210713def validate_log_file(self, logname, header_errors=0):10714"""Validate the contents of a log file"""10715# read the downloaded log - it must parse without error10716class Capturing(list):10717def __enter__(self):10718self._stderr = sys.stderr10719sys.stderr = self._stringio = io.StringIO()10720return self1072110722def __exit__(self, *args):10723self.extend(self._stringio.getvalue().splitlines())10724del self._stringio # free up some memory10725sys.stderr = self._stderr1072610727with Capturing() as df_output:10728try:10729mlog = mavutil.mavlink_connection(logname)10730while True:10731m = mlog.recv_match()10732if m is None:10733break10734except Exception as e:10735raise NotAchievedException("Error reading log file %s: %s" % (logname, str(e)))1073610737herrors = 01073810739for msg in df_output:10740if msg.startswith("bad header") or msg.startswith("unknown msg type"):10741herrors = herrors + 11074210743if herrors > header_errors:10744raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors))1074510746def DataFlashErase(self):10747"""Test that erasing the dataflash chip and creating a new log is error free"""10748mavproxy = self.start_mavproxy()1074910750ex = None10751self.context_push()10752try:10753self.set_parameter("LOG_BACKEND_TYPE", 4)10754self.reboot_sitl()10755mavproxy.send("module load log\n")10756mavproxy.send("log erase\n")10757mavproxy.expect("Chip erase complete")10758self.set_parameter("LOG_DISARMED", 1)10759self.delay_sim_time(3)10760self.set_parameter("LOG_DISARMED", 0)10761mavproxy.send("log download 1 logs/dataflash-log-erase.BIN\n")10762mavproxy.expect("Finished downloading", timeout=120)10763# read the downloaded log - it must parse without error10764self.validate_log_file("logs/dataflash-log-erase.BIN")1076510766self.start_subtest("Test file wrapping results in a valid file")10767# roughly 4mb10768self.set_parameter("LOG_FILE_DSRMROT", 1)10769self.set_parameter("LOG_BITMASK", 131071)10770self.wait_ready_to_arm()10771if self.is_copter() or self.is_plane():10772self.set_autodisarm_delay(0)10773self.arm_vehicle()10774self.delay_sim_time(30)10775self.disarm_vehicle()10776# roughly 4mb10777self.arm_vehicle()10778self.delay_sim_time(30)10779self.disarm_vehicle()10780# roughly 9mb, should wrap around10781self.arm_vehicle()10782self.delay_sim_time(50)10783self.disarm_vehicle()10784# make sure we have finished logging10785self.delay_sim_time(15)10786mavproxy.send("log list\n")10787try:10788mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)10789except pexpect.TIMEOUT as e:10790if self.sitl_is_running():10791self.progress("SITL is running")10792else:10793self.progress("SITL is NOT running")10794raise NotAchievedException("Received %s" % str(e))10795if int(mavproxy.match.group(2)) != 3:10796raise NotAchievedException("Expected 3 logs got %s" % (mavproxy.match.group(2)))1079710798mavproxy.send("log download 1 logs/dataflash-log-erase2.BIN\n")10799mavproxy.expect("Finished downloading", timeout=120)10800self.validate_log_file("logs/dataflash-log-erase2.BIN", 1)1080110802mavproxy.send("log download latest logs/dataflash-log-erase3.BIN\n")10803mavproxy.expect("Finished downloading", timeout=120)10804self.validate_log_file("logs/dataflash-log-erase3.BIN", 1)1080510806# clean up10807mavproxy.send("log erase\n")10808mavproxy.expect("Chip erase complete")1080910810# clean up10811mavproxy.send("log erase\n")10812mavproxy.expect("Chip erase complete")1081310814except Exception as e:10815self.print_exception_caught(e)10816ex = e1081710818mavproxy.send("module unload log\n")1081910820self.context_pop()10821self.reboot_sitl()1082210823self.stop_mavproxy(mavproxy)1082410825if ex is not None:10826raise ex1082710828def ArmFeatures(self):10829'''Arm features'''10830# TEST ARMING/DISARM10831self.delay_sim_time(12) # wait for gyros/accels to be happy10832if self.get_parameter("ARMING_SKIPCHK") != 0 and not self.is_sub():10833raise ValueError("Arming skipped checks should be 0")10834if not self.is_sub() and not self.is_tracker():10835self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests10836if self.is_copter():10837interlock_channel = 8 # Plane got flighmode_ch on channel 810838if not self.is_heli(): # heli don't need interlock option10839interlock_channel = 910840self.set_parameter("RC%u_OPTION" % interlock_channel, 32)10841self.set_rc(interlock_channel, 1000)10842self.zero_throttle()10843# Disable auto disarm for next tests10844# Rover and Sub don't have auto disarm10845if self.is_copter() or self.is_plane():10846self.set_autodisarm_delay(0)10847self.start_subtest("Test normal arm and disarm features")10848self.wait_ready_to_arm()10849self.progress("default arm_vehicle() call")10850if not self.arm_vehicle():10851raise NotAchievedException("Failed to ARM")10852self.progress("default disarm_vehicle() call")10853self.disarm_vehicle()1085410855self.start_subtest("Arm/disarm vehicle with COMMAND_INT")10856self.run_cmd_int(10857mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10858p1=1, # ARM10859)10860self.run_cmd_int(10861mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,10862p1=0, # DISARM10863)1086410865self.progress("arm with mavproxy")10866mavproxy = self.start_mavproxy()10867if not self.mavproxy_arm_vehicle(mavproxy):10868raise NotAchievedException("Failed to ARM")10869self.progress("disarm with mavproxy")10870self.mavproxy_disarm_vehicle(mavproxy)10871self.stop_mavproxy(mavproxy)1087210873if not self.is_sub():10874self.start_subtest("Test arm with rc input")10875self.arm_motors_with_rc_input()10876self.progress("disarm with rc input")10877if self.is_balancebot():10878self.progress("balancebot can't disarm with RC input")10879self.disarm_vehicle()10880else:10881self.disarm_motors_with_rc_input()1088210883self.start_subtest("Test arm and disarm with switch")10884arming_switch = 710885self.set_parameter("RC%d_OPTION" % arming_switch, 153)10886self.set_rc(arming_switch, 1000)10887# delay so a transition is seen by the RC switch code:10888self.delay_sim_time(0.5)10889self.arm_motors_with_switch(arming_switch)10890self.disarm_motors_with_switch(arming_switch)10891self.set_rc(arming_switch, 1000)1089210893if self.is_copter():10894self.start_subtest("Test arming failure with throttle too high")10895self.set_rc(3, 1800)10896try:10897if self.arm_vehicle():10898raise NotAchievedException("Armed when throttle too high")10899except ValueError:10900pass10901try:10902self.arm_motors_with_rc_input()10903except NotAchievedException:10904pass10905if self.armed():10906raise NotAchievedException(10907"Armed via RC when throttle too high")10908try:10909self.arm_motors_with_switch(arming_switch)10910except NotAchievedException:10911pass10912if self.armed():10913raise NotAchievedException("Armed via RC when switch too high")10914self.zero_throttle()10915self.set_rc(arming_switch, 1000)1091610917# Sub doesn't have 'stick commands'10918self.start_subtest("Test arming failure with ARMING_RUDDER=0")10919self.set_parameter("ARMING_RUDDER", 0)10920try:10921self.arm_motors_with_rc_input()10922except NotAchievedException:10923pass10924if self.armed():10925raise NotAchievedException(10926"Armed with rudder when ARMING_RUDDER=0")10927self.start_subtest("Test disarming failure with ARMING_RUDDER=0")10928self.arm_vehicle()10929try:10930self.disarm_motors_with_rc_input(watch_for_disabled=True)10931except NotAchievedException:10932pass10933if not self.armed():10934raise NotAchievedException(10935"Disarmed with rudder when ARMING_RUDDER=0")10936self.disarm_vehicle()10937self.wait_heartbeat()10938self.start_subtest("Test disarming failure with ARMING_RUDDER=1")10939self.set_parameter("ARMING_RUDDER", 1)10940self.arm_vehicle()10941try:10942self.disarm_motors_with_rc_input()10943except NotAchievedException:10944pass10945if not self.armed():10946raise NotAchievedException(10947"Disarmed with rudder with ARMING_RUDDER=1")10948self.disarm_vehicle()10949self.wait_heartbeat()10950self.set_parameter("ARMING_RUDDER", 2)1095110952if self.is_copter():10953self.start_subtest("Test arming failure with interlock enabled")10954self.set_rc(interlock_channel, 2000)10955try:10956self.arm_motors_with_rc_input()10957except NotAchievedException:10958pass10959if self.armed():10960raise NotAchievedException(10961"Armed with RC input when interlock enabled")10962try:10963self.arm_motors_with_switch(arming_switch)10964except NotAchievedException:10965pass10966if self.armed():10967raise NotAchievedException("Armed with switch when interlock enabled")10968self.disarm_vehicle()10969self.wait_heartbeat()10970self.set_rc(arming_switch, 1000)10971self.set_rc(interlock_channel, 1000)10972if self.is_heli():10973self.start_subtest("Test motor interlock enable can't be set while disarmed")10974self.set_rc(interlock_channel, 2000)10975channel_field = "servo%u_raw" % interlock_channel10976interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel)10977tstart = self.get_sim_time()10978while True:10979if self.get_sim_time_cached() - tstart > 20:10980self.set_rc(interlock_channel, 1000)10981break # success!10982m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',10983blocking=True,10984timeout=2)10985if m is None:10986continue10987m_value = getattr(m, channel_field, None)10988if m_value is None:10989self.set_rc(interlock_channel, 1000)10990raise ValueError("Message has no %s field" %10991channel_field)10992self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %10993(channel_field, m_value, interlock_value))10994if m_value != interlock_value:10995self.set_rc(interlock_channel, 1000)10996raise NotAchievedException("Motor interlock was changed while disarmed")10997self.set_rc(interlock_channel, 1000)1099810999self.start_subtest("Test all mode arming")11000self.wait_ready_to_arm()1100111002if self.arming_test_mission() is not None:11003self.load_mission(self.arming_test_mission())1100411005for mode in self.mav.mode_mapping():11006self.drain_mav()11007self.start_subtest("Mode : %s" % mode)11008if mode == "FOLLOW":11009self.set_parameter("FOLL_ENABLE", 1)11010if mode in self.get_normal_armable_modes_list():11011self.progress("Armable mode : %s" % mode)11012self.change_mode(mode)11013self.arm_vehicle()11014self.disarm_vehicle()11015self.progress("PASS arm mode : %s" % mode)11016if mode in self.get_not_armable_mode_list():11017if mode in self.get_not_disarmed_settable_modes_list():11018self.progress("Not settable mode : %s" % mode)11019try:11020self.change_mode(mode, timeout=15)11021except AutoTestTimeoutException:11022self.progress("PASS not able to set mode : %s disarmed" % mode)11023except ValueError:11024self.progress("PASS not able to set mode : %s disarmed" % mode)11025else:11026self.progress("Not armable mode : %s" % mode)11027self.change_mode(mode)11028self.run_cmd(11029mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,11030p1=1, # ARM11031want_result=mavutil.mavlink.MAV_RESULT_FAILED,11032)11033self.progress("PASS not able to arm in mode : %s" % mode)11034if mode in self.get_position_armable_modes_list():11035self.progress("Armable mode needing Position : %s" % mode)11036self.wait_ekf_happy()11037self.change_mode(mode)11038self.arm_vehicle()11039self.wait_heartbeat()11040self.disarm_vehicle()11041self.progress("PASS arm mode : %s" % mode)11042self.progress("Not armable mode without Position : %s" % mode)11043self.wait_gps_disable()11044self.change_mode(mode)11045self.run_cmd(11046mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,11047p1=1, # ARM11048want_result=mavutil.mavlink.MAV_RESULT_FAILED,11049)11050self.set_parameter("SIM_GPS1_ENABLE", 1)11051self.wait_ekf_happy() # EKF may stay unhappy for a while11052self.progress("PASS not able to arm without Position in mode : %s" % mode)11053if mode in self.get_no_position_not_settable_modes_list():11054self.progress("Setting mode need Position : %s" % mode)11055self.wait_ekf_happy()11056self.wait_gps_disable()11057try:11058self.change_mode(mode, timeout=15)11059except AutoTestTimeoutException:11060self.set_parameter("SIM_GPS1_ENABLE", 1)11061self.progress("PASS not able to set mode without Position : %s" % mode)11062except ValueError:11063self.set_parameter("SIM_GPS1_ENABLE", 1)11064self.progress("PASS not able to set mode without Position : %s" % mode)11065if mode == "FOLLOW":11066self.set_parameter("FOLL_ENABLE", 0)11067self.change_mode(self.default_mode())11068if self.armed():11069self.disarm_vehicle()1107011071# we should find at least one Armed event and one disarmed11072# event, and at least one ARM message for arm and disarm11073wants = set([11074("Armed EV message", "EV", lambda e : e.Id == 10),11075("Disarmed EV message", "EV", lambda e : e.Id == 11),11076("Armed ARM message", "ARM", lambda a : a.ArmState == 1),11077("Disarmed ARM message", "ARM", lambda a : a.ArmState == 0),11078])1107911080dfreader = self.dfreader_for_current_onboard_log()11081types = set()11082for (name, msgtype, l) in wants:11083types.add(msgtype)1108411085while True:11086m = dfreader.recv_match(type=types)11087if m is None:11088break11089wantscopy = copy.copy(wants)11090for want in wantscopy:11091(name, msgtype, l) = want11092if m.get_type() != msgtype:11093continue11094if l(m):11095self.progress("Found %s" % name)11096wants.discard(want)11097if len(wants) == 0:11098break1109911100if len(wants):11101msg = ", ".join([x[0] for x in wants])11102raise NotAchievedException("Did not find (%s)" % msg)1110311104self.progress("ALL PASS")11105# TODO : Test arming magic;1110611107def measure_message_rate(self, victim_message, timeout=10, mav=None):11108if mav is None:11109mav = self.mav11110tstart = self.get_sim_time()11111count = 011112while self.get_sim_time_cached() < tstart + timeout:11113m = mav.recv_match(11114type=victim_message,11115blocking=True,11116timeout=0.111117)11118if m is not None:11119count += 111120if mav != self.mav:11121self.drain_mav(self.mav)1112211123time_delta = self.get_sim_time_cached() - tstart11124self.progress("%s count after %f seconds: %u" %11125(victim_message, time_delta, count))11126return count/time_delta1112711128def rate_to_interval_us(self, rate):11129return 1/float(rate)*1000000.01113011131def interval_us_to_rate(self, interval):11132if interval == 0:11133raise ValueError("Zero interval is infinite rate")11134return 1000000.0/float(interval)1113511136def set_message_rate_hz(self, id, rate_hz, mav=None, run_cmd=None):11137'''set a message rate in Hz; 0 for original, -1 to disable'''11138if run_cmd is None:11139run_cmd = self.run_cmd11140if isinstance(id, str):11141id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id)11142if rate_hz == 0 or rate_hz == -1:11143set_interval = rate_hz11144else:11145set_interval = self.rate_to_interval_us(rate_hz)11146run_cmd(11147mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,11148p1=id,11149p2=set_interval,11150mav=mav,11151)1115211153def get_message_rate_hz(self, id, mav=None, run_cmd=None):11154'''return rate message is being sent, in Hz'''11155if run_cmd is None:11156run_cmd = self.run_cmd1115711158interval = self.get_message_interval(id, mav=mav, run_cmd=run_cmd)11159return self.interval_us_to_rate(interval)1116011161def send_get_message_interval(self, victim_message, mav=None):11162if mav is None:11163mav = self.mav11164if isinstance(victim_message, str):11165victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)11166mav.mav.command_long_send(111671,111681,11169mavutil.mavlink.MAV_CMD_GET_MESSAGE_INTERVAL,111701, # confirmation11171float(victim_message),111720,111730,111740,111750,111760,111770)1117811179def get_message_interval(self, victim_message, mav=None, run_cmd=None):11180'''returns message interval in microseconds'''11181if run_cmd is None:11182run_cmd = self.run_cmd1118311184self.send_get_message_interval(victim_message, mav=mav)11185m = self.assert_receive_message('MESSAGE_INTERVAL', mav=mav)1118611187if isinstance(victim_message, str):11188victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)11189if m.message_id != victim_message:11190raise NotAchievedException(f"Unexpected ID in MESSAGE_INTERVAL (want={victim_message}, got={m.message_id}")1119111192return m.interval_us1119311194def set_message_interval(self, victim_message, interval_us, mav=None):11195'''sets message interval in microseconds'''11196if isinstance(victim_message, str):11197victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)11198self.run_cmd(11199mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,11200p1=victim_message,11201p2=interval_us,11202mav=mav,11203)1120411205def test_rate(self,11206desc,11207in_rate,11208expected_rate11209, mav=None,11210victim_message="VFR_HUD",11211ndigits=0,11212message_rate_sample_period=10):11213if mav is None:11214mav = self.mav1121511216self.progress("###### %s" % desc)11217self.progress("Setting rate to %f" % round(in_rate, ndigits=ndigits))1121811219self.set_message_rate_hz(victim_message, in_rate, mav=mav)1122011221new_measured_rate = self.measure_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav)11222self.progress(11223"Measured rate: %f (want %f)" %11224(round(new_measured_rate, ndigits=ndigits),11225round(expected_rate, ndigits=ndigits))11226)11227notachieved_ex = None11228if round(new_measured_rate, ndigits=ndigits) != round(expected_rate, ndigits=ndigits):11229notachieved_ex = NotAchievedException(11230"Rate not achieved (got %f want %f)" %11231(round(new_measured_rate, ndigits),11232round(expected_rate, ndigits)))1123311234# make sure get_message_interval works:11235self.send_get_message_interval(victim_message, mav=mav)1123611237m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=30, mav=mav)1123811239if in_rate == 0:11240want = self.rate_to_interval_us(expected_rate)11241elif in_rate == -1:11242want = in_rate11243else:11244want = self.rate_to_interval_us(in_rate)1124511246if m.interval_us != want:11247raise NotAchievedException("Did not read same interval back from autopilot: want=%d got=%d)" %11248(want, m.interval_us))11249m = self.assert_receive_message('COMMAND_ACK', mav=mav)11250if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:11251raise NotAchievedException("Expected ACCEPTED for reading message interval")1125211253if notachieved_ex is not None:11254raise notachieved_ex1125511256def SET_MESSAGE_INTERVAL(self):11257'''Test MAV_CMD_SET_MESSAGE_INTERVAL'''11258self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger11259self.reboot_sitl() # needed for CAM1_TYPE to take effect11260self.start_subtest('Basic tests')11261self.test_set_message_interval_basic()11262self.start_subtest('Many-message tests')11263self.test_set_message_interval_many()1126411265def MESSAGE_INTERVAL_COMMAND_INT(self):11266'''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT'''11267original_rate = round(self.measure_message_rate("VFR_HUD", 20))11268self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)11269if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1:11270raise NotAchievedException("Did not set rate")1127111272# Try setting a rate well beyond SCHED_LOOP_RATE11273self.run_cmd(11274mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,11275p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD,11276p2=self.rate_to_interval_us(800),11277want_result=mavutil.mavlink.MAV_RESULT_DENIED,11278)1127911280self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT")11281# 148 is AUTOPILOT_VERSION:11282self.context_collect('AUTOPILOT_VERSION')11283self.run_cmd_int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, 148)11284self.delay_sim_time(2)11285count = len(self.context_collection('AUTOPILOT_VERSION'))11286if count != 1:11287raise NotAchievedException(f"Did not get single AUTOPILOT_VERSION message (count={count}")1128811289def test_set_message_interval_many(self):11290messages = [11291'CAMERA_FEEDBACK',11292'RAW_IMU',11293'ATTITUDE',11294]11295ex = None11296try:11297rate = 511298for message in messages:11299self.set_message_rate_hz(message, rate)11300for message in messages:11301self.assert_message_rate_hz(message, rate)11302except Exception as e:11303self.print_exception_caught(e)11304ex = e1130511306# reset message rates to default:11307for message in messages:11308self.set_message_rate_hz(message, -1)1130911310if ex is not None:11311raise ex1131211313def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0, mav=None):11314if mav is None:11315mav = self.mav11316self.drain_mav(mav)11317rate = round(self.measure_message_rate(message, sample_period, mav=mav), ndigits=ndigits)11318self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits)))11319if rate != want_rate:11320raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate))1132111322def test_set_message_interval_basic(self):11323ex = None11324try:11325rate = round(self.measure_message_rate("VFR_HUD", 20))11326self.progress("Initial rate: %u" % rate)1132711328self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD")11329# this assumes the streamrates have not been played with:11330self.test_rate("Resetting original rate using 0-value", 0, rate)11331self.test_rate("Disabling using -1-value", -1, 0)11332self.test_rate("Resetting original rate", 0, rate)1133311334self.progress("try getting a message which is not ordinarily streamed out")11335rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))11336if rate != 0:11337raise PreconditionFailedException("Already getting CAMERA_FEEDBACK")11338self.progress("try various message rates")11339for want_rate in range(5, 14):11340self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,11341want_rate)11342self.assert_message_rate_hz('CAMERA_FEEDBACK', want_rate)1134311344self.progress("try at the main loop rate")11345# have to reset the speedup as MAVProxy can't keep up otherwise11346old_speedup = self.get_parameter("SIM_SPEEDUP")11347self.set_parameter("SIM_SPEEDUP", 1.0)11348# ArduPilot currently limits message rate to 80% of main loop rate:11349want_rate = self.get_parameter("SCHED_LOOP_RATE") * 0.811350self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,11351want_rate)11352rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))11353self.set_parameter("SIM_SPEEDUP", old_speedup)11354self.progress("Want=%f got=%f" % (want_rate, rate))11355if abs(rate - want_rate) > 2:11356raise NotAchievedException("Did not get expected rate")1135711358self.drain_mav()1135911360non_existant_id = 14511361self.send_get_message_interval(non_existant_id)11362m = self.assert_receive_message('MESSAGE_INTERVAL')11363if m.interval_us != 0:11364raise NotAchievedException("Supposed to get 0 back for unsupported stream")11365m = self.assert_receive_message('COMMAND_ACK')11366if m.result != mavutil.mavlink.MAV_RESULT_FAILED:11367raise NotAchievedException("Getting rate of unsupported message is a failure")1136811369except Exception as e:11370self.print_exception_caught(e)11371ex = e1137211373self.progress("Resetting CAMERA_FEEDBACK rate to default rate")11374self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, 0)11375self.assert_message_rate_hz('CAMERA_FEEDBACK', 0)1137611377if ex is not None:11378raise ex1137911380def send_poll_message(self, message_id, target_sysid=None, target_compid=None, quiet=False, mav=None):11381if mav is None:11382mav = self.mav11383if isinstance(message_id, str):11384message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)11385self.send_cmd(11386mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,11387p1=message_id,11388target_sysid=target_sysid,11389target_compid=target_compid,11390quiet=quiet,11391mav=mav,11392)1139311394def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None):11395if mav is None:11396mav = self.mav11397if target_sysid is None:11398target_sysid = self.sysid_thismav()11399if target_compid is None:11400target_compid = 111401if isinstance(message_id, str):11402message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)11403tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work11404self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid)11405self.run_cmd_get_ack(11406mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,11407mavutil.mavlink.MAV_RESULT_ACCEPTED,11408timeout,11409quiet=quiet,11410mav=mav,11411)11412while True:11413if self.get_sim_time_cached() - tstart > timeout:11414raise NotAchievedException("Did not receive polled message")11415m = mav.recv_match(blocking=True,11416timeout=0.1)11417if self.mav != mav:11418self.drain_mav()11419if m is None:11420continue11421if m.id != message_id:11422continue11423if (m.get_srcSystem() != target_sysid or11424m.get_srcComponent() != target_compid):11425continue11426return m1142711428def get_messages_frame(self, msg_names):11429'''try to get a "frame" of named messages - a set of messages as close11430in time as possible'''11431msgs = {}1143211433def get_msgs(mav, m):11434t = m.get_type()11435if t in msg_names:11436msgs[t] = m11437self.do_timesync_roundtrip()11438self.install_message_hook(get_msgs)11439for msg_name in msg_names:11440self.send_poll_message(msg_name)11441while True:11442self.mav.recv_match(blocking=True)11443if len(msgs.keys()) == len(msg_names):11444break1144511446self.remove_message_hook(get_msgs)1144711448return msgs1144911450def REQUEST_MESSAGE(self, timeout=60):11451'''Test MAV_CMD_REQUEST_MESSAGE'''11452self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger11453self.reboot_sitl() # needed for CAM1_TYPE to take effect11454rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 10))11455if rate != 0:11456raise PreconditionFailedException("Receiving camera feedback")11457self.poll_message("CAMERA_FEEDBACK")1145811459def clear_mission(self, mission_type, target_system=1, target_component=1):11460'''clear mision_type from autopilot. Note that this does NOT actually11461send a MISSION_CLEAR_ALL message11462'''11463if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_ALL:11464# recurse11465if not self.is_tracker() and not self.is_blimp():11466self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)11467if not self.is_blimp():11468self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)11469if not self.is_sub() and not self.is_tracker() and not self.is_blimp():11470self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)11471self.last_wp_load = time.time()11472return1147311474self.mav.mav.mission_count_send(target_system,11475target_component,114760,11477mission_type)11478self.assert_received_message_field_values('MISSION_ACK', {11479"target_system": self.mav.mav.srcSystem,11480"target_component": self.mav.mav.srcComponent,11481"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,11482})1148311484if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:11485self.last_wp_load = time.time()1148611487def clear_fence_using_mavproxy(self, mavproxy, timeout=10):11488mavproxy.send("fence clear\n")11489tstart = self.get_sim_time_cached()11490while True:11491now = self.get_sim_time_cached()11492if now - tstart > timeout:11493raise AutoTestTimeoutException("FENCE_TOTAL did not go to zero")11494if self.get_parameter("FENCE_TOTAL") == 0:11495break1149611497def clear_fence(self):11498self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1149911500# Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa11501def ConfigErrorLoop(self):11502'''test the sensor config error loop works and that parameter sets are persistent'''11503parameter_name = "SERVO8_MIN"11504old_parameter_value = self.get_parameter(parameter_name)11505old_sim_baro_count = self.get_parameter("SIM_BARO_COUNT")11506new_parameter_value = old_parameter_value + 511507ex = None11508try:11509self.set_parameter("STAT_BOOTCNT", 0)11510self.set_parameter("SIM_BARO_COUNT", -1)1151111512if self.is_tracker():11513# starts armed...11514self.progress("Disarming tracker")11515self.disarm_vehicle(force=True)1151611517self.reboot_sitl(required_bootcount=1)11518self.progress("Waiting for 'Config error'")11519# SYSTEM_TIME not sent in config error loop:11520self.wait_statustext("Config error", wallclock_timeout=True)11521self.progress("Setting %s to %f" % (parameter_name, new_parameter_value))11522self.set_parameter(parameter_name, new_parameter_value)11523except Exception as e:11524ex = e1152511526self.progress("Resetting SIM_BARO_COUNT")11527self.set_parameter("SIM_BARO_COUNT", old_sim_baro_count)1152811529if self.is_tracker():11530# starts armed...11531self.progress("Disarming tracker")11532self.disarm_vehicle(force=True)1153311534self.progress("Calling reboot-sitl ")11535self.reboot_sitl(required_bootcount=2)1153611537if ex is not None:11538raise ex1153911540if self.get_parameter(parameter_name) != new_parameter_value:11541raise NotAchievedException("Parameter value did not stick")1154211543def InitialMode(self):11544'''Test initial mode switching'''11545if self.is_copter():11546init_mode = (9, "LAND")11547if self.is_rover():11548init_mode = (4, "HOLD")11549if self.is_plane():11550init_mode = (13, "TAKEOFF")11551if self.is_tracker():11552init_mode = (1, "STOP")11553if self.is_sub():11554return # NOT Supported yet11555self.context_push()11556self.set_parameter("SIM_RC_FAIL", 1)11557self.progress("Setting INITIAL_MODE to %s" % init_mode[1])11558self.set_parameter("INITIAL_MODE", init_mode[0])11559self.reboot_sitl()11560self.wait_mode(init_mode[1])11561self.progress("Testing back mode switch")11562self.set_parameter("SIM_RC_FAIL", 0)11563self.wait_for_mode_switch_poll()11564self.context_pop()11565self.reboot_sitl()1156611567def Gripper(self):11568'''Test gripper'''11569self.GripperType(1) # servo11570self.GripperType(2) # EPM1157111572def GripperType(self, gripper_type):11573'''test specific gripper type'''11574self.context_push()11575self.set_parameters({11576"GRIP_ENABLE": 1,11577"GRIP_GRAB": 2000,11578"GRIP_RELEASE": 1000,11579"GRIP_TYPE": gripper_type,11580"SIM_GRPS_ENABLE": 1,11581"SIM_GRPS_PIN": 8,11582"SERVO8_FUNCTION": 28,11583"SERVO8_MIN": 1000,11584"SERVO8_MAX": 2000,11585"SERVO9_MIN": 1000,11586"SERVO9_MAX": 2000,11587"RC9_OPTION": 19,11588})11589self.set_rc(9, 1500)11590self.reboot_sitl()11591self.progress("Waiting for ready to arm")11592self.wait_ready_to_arm()11593self.progress("Test gripper with RC9_OPTION")11594self.progress("Releasing load")11595# non strict string matching because of catching text issue....11596self.context_collect('STATUSTEXT')11597self.set_rc(9, 1000)11598self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)11599self.progress("Grabbing load")11600self.set_rc(9, 2000)11601self.wait_text("Gripper load grabb", check_context=True)11602self.context_clear_collection('STATUSTEXT')11603self.progress("Releasing load")11604self.set_rc(9, 1000)11605self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)11606self.progress("Grabbing load")11607self.set_rc(9, 2000)11608self.wait_text("Gripper load grabb", check_context=True)11609self.progress("Test gripper with Mavlink cmd")1161011611self.context_collect('STATUSTEXT')11612self.progress("Releasing load")11613self.run_cmd(11614mavutil.mavlink.MAV_CMD_DO_GRIPPER,11615p1=1,11616p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE11617)11618self.wait_text("Gripper load releas(ed|ing)", check_context=True, regex=True)11619self.progress("Grabbing load")11620self.run_cmd(11621mavutil.mavlink.MAV_CMD_DO_GRIPPER,11622p1=1,11623p2=mavutil.mavlink.GRIPPER_ACTION_GRAB11624)11625self.wait_text("Gripper load grabb", check_context=True)1162611627self.context_clear_collection('STATUSTEXT')11628self.progress("Releasing load")11629self.run_cmd_int(11630mavutil.mavlink.MAV_CMD_DO_GRIPPER,11631p1=1,11632p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE11633)11634self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)1163511636self.progress("Grabbing load")11637self.run_cmd_int(11638mavutil.mavlink.MAV_CMD_DO_GRIPPER,11639p1=1,11640p2=mavutil.mavlink.GRIPPER_ACTION_GRAB11641)11642self.wait_text("Gripper load grabb", check_context=True)1164311644self.context_pop()11645self.reboot_sitl()1164611647def TestLocalHomePosition(self):11648"""Test local home position is sent in HOME_POSITION message"""11649self.context_push()11650self.wait_ready_to_arm()1165111652# set home to a new location11653self.mav.mav.command_long_send(1,116541,11655mavutil.mavlink.MAV_CMD_DO_SET_HOME,116560,116570,116580,116590,116600,11661-35.357466,11662149.142589,11663630)1166411665# check home after home set11666m = self.assert_receive_message("HOME_POSITION", timeout=5)11667if abs(m.x) < 10 or abs(m.y) < 10 or abs(m.z) < 10:11668raise NotAchievedException("Failed to get local home position: (got=%u, %u, %u)", m.x, m.y, m.z)11669else:11670self.progress("Received local home position successfully: (got=%f, %f, %f)" %11671(m.x, m.y, m.z))1167211673self.context_pop()11674self.reboot_sitl()1167511676def install_terrain_handlers_context(self):11677'''install a message handler into the current context which will11678listen for an fulfill terrain requests from ArduPilot. Will11679die if the data is not available - but11680self.terrain_in_offline_mode can be set to true in the11681constructor to change this behaviour11682this should be called at the very top of your test context!11683'''1168411685def check_terrain_requests(mav, m):11686if m.get_type() != 'TERRAIN_REQUEST':11687return11688self.progress("Processing TERRAIN_REQUEST (%s)" %11689self.dump_message_verbose(m))11690# swiped from mav_terrain.py11691for bit in range(56):11692if m.mask & (1 << bit) == 0:11693continue1169411695lat = m.lat * 1.0e-711696lon = m.lon * 1.0e-711697bit_spacing = m.grid_spacing * 411698(lat, lon) = mp_util.gps_offset(lat, lon,11699east=bit_spacing * (bit % 8),11700north=bit_spacing * (bit // 8))11701data = []11702for i in range(4*4):11703y = i % 411704x = i // 411705(lat2, lon2) = mp_util.gps_offset(lat, lon,11706east=m.grid_spacing * y,11707north=m.grid_spacing * x)11708# if we are in online mode then we'll try to fetch11709# from the internet into the cache dir:11710for i in range(120):11711alt = self.elevationmodel.GetElevation(lat2, lon2)11712if alt is not None:11713break11714if self.terrain_in_offline_mode:11715break11716self.progress("No elevation data for (%f %f); retry" %11717(lat2, lon2))11718time.sleep(1)11719if alt is None:11720# no data - we can't send the packet11721raise ValueError("No elevation data for (%f %f)" % (lat2, lon2))11722data.append(int(alt))11723self.terrain_data_messages_sent += 111724self.mav.mav.terrain_data_send(m.lat,11725m.lon,11726m.grid_spacing,11727bit,11728data)1172911730self.install_message_hook_context(check_terrain_requests)1173111732def install_messageprinter_handlers_context(self, messages):11733'''monitor incoming messages, print them out'''11734def check_messages(mav, m):11735if m.get_type() not in messages:11736return11737self.progress(self.dump_message_verbose(m))1173811739self.install_message_hook_context(check_messages)1174011741def SetpointGlobalPos(self, timeout=100):11742"""Test set position message in guided mode."""11743# Disable heading and yaw test on rover type1174411745if self.is_rover():11746test_alt = True11747test_heading = False11748test_yaw_rate = False11749else:11750test_alt = True11751test_heading = True11752test_yaw_rate = True1175311754self.install_terrain_handlers_context()1175511756self.set_parameter("FS_GCS_ENABLE", 0)11757self.change_mode("GUIDED")11758self.wait_ready_to_arm()11759self.arm_vehicle()1176011761if self.is_copter() or self.is_heli():11762self.user_takeoff(alt_min=50)1176311764targetpos = self.mav.location()11765wp_accuracy = None11766if self.is_copter() or self.is_heli():11767wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)11768wp_accuracy = wp_accuracy * 0.01 # cm to m11769if self.is_plane() or self.is_rover():11770wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)11771if wp_accuracy is None:11772raise ValueError()1177311774def to_alt_frame(alt, mav_frame):11775if mav_frame in ["MAV_FRAME_GLOBAL_RELATIVE_ALT",11776"MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",11777"MAV_FRAME_GLOBAL_TERRAIN_ALT",11778"MAV_FRAME_GLOBAL_TERRAIN_ALT_INT"]:11779home = self.home_position_as_mav_location()11780return alt - home.alt11781else:11782return alt1178311784def send_target_position(lat, lng, alt, mav_frame):11785self.mav.mav.set_position_target_global_int_send(117860, # timestamp11787self.sysid_thismav(), # target system_id117881, # target component id11789mav_frame,11790MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11791MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11792MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11793MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11794int(lat * 1.0e7), # lat11795int(lng * 1.0e7), # lon11796alt, # alt117970, # vx117980, # vy117990, # vz118000, # afx118010, # afy118020, # afz118030, # yaw118040, # yawrate11805)1180611807def testpos(self, targetpos: mavutil.location, test_alt: bool, frame_name: str, frame):11808send_target_position(targetpos.lat, targetpos.lng, to_alt_frame(targetpos.alt, frame_name), frame)11809self.wait_location(11810targetpos,11811accuracy=wp_accuracy,11812timeout=timeout,11813height_accuracy=(2 if test_alt else None),11814minimum_duration=2,11815)1181611817for frame in MAV_FRAMES_TO_TEST:11818frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name11819self.start_subtest("Testing Set Position in %s" % frame_name)11820self.start_subtest("Changing Latitude")11821targetpos.lat += 0.000111822if test_alt:11823targetpos.alt += 511824testpos(self, targetpos, test_alt, frame_name, frame)1182511826self.start_subtest("Changing Longitude")11827targetpos.lng += 0.000111828if test_alt:11829targetpos.alt -= 511830testpos(self, targetpos, test_alt, frame_name, frame)1183111832self.start_subtest("Revert Latitude")11833targetpos.lat -= 0.000111834if test_alt:11835targetpos.alt += 511836testpos(self, targetpos, test_alt, frame_name, frame)1183711838self.start_subtest("Revert Longitude")11839targetpos.lng -= 0.000111840if test_alt:11841targetpos.alt -= 511842testpos(self, targetpos, test_alt, frame_name, frame)1184311844if test_heading:11845self.start_subtest("Testing Yaw targeting in %s" % frame_name)11846self.progress("Changing Latitude and Heading")11847targetpos.lat += 0.000111848if test_alt:11849targetpos.alt += 511850self.mav.mav.set_position_target_global_int_send(118510, # timestamp11852self.sysid_thismav(), # target system_id118531, # target component id11854frame,11855MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11856MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11857MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11858int(targetpos.lat * 1.0e7), # lat11859int(targetpos.lng * 1.0e7), # lon11860to_alt_frame(targetpos.alt, frame_name), # alt118610, # vx118620, # vy118630, # vz118640, # afx118650, # afy118660, # afz11867math.radians(42), # yaw118680, # yawrate11869)11870self.wait_location(11871targetpos,11872accuracy=wp_accuracy,11873timeout=timeout,11874height_accuracy=(2 if test_alt else None),11875minimum_duration=2,11876)11877self.wait_heading(42, minimum_duration=5, timeout=timeout)1187811879self.start_subtest("Revert Latitude and Heading")11880targetpos.lat -= 0.000111881if test_alt:11882targetpos.alt -= 511883self.mav.mav.set_position_target_global_int_send(118840, # timestamp11885self.sysid_thismav(), # target system_id118861, # target component id11887frame,11888MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11889MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11890MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,11891int(targetpos.lat * 1.0e7), # lat11892int(targetpos.lng * 1.0e7), # lon11893to_alt_frame(targetpos.alt, frame_name), # alt118940, # vx118950, # vy118960, # vz118970, # afx118980, # afy118990, # afz11900math.radians(0), # yaw119010, # yawrate11902)11903self.wait_location(11904targetpos,11905accuracy=wp_accuracy,11906timeout=timeout,11907height_accuracy=(2 if test_alt else None),11908minimum_duration=2,11909)11910self.wait_heading(0, minimum_duration=5, timeout=timeout)1191111912if test_yaw_rate:11913self.start_subtest("Testing Yaw Rate targeting in %s" % frame_name)1191411915def send_yaw_rate(rate, target=None):11916self.mav.mav.set_position_target_global_int_send(119170, # timestamp11918self.sysid_thismav(), # target system_id119191, # target component id11920frame,11921MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |11922MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11923MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,11924int(targetpos.lat * 1.0e7), # lat11925int(targetpos.lng * 1.0e7), # lon11926to_alt_frame(targetpos.alt, frame_name), # alt119270, # vx119280, # vy119290, # vz119300, # afx119310, # afy119320, # afz119330, # yaw11934rate, # yawrate in rad/s11935)1193611937self.start_subtest("Changing Latitude and Yaw rate")11938target_rate = 1.0 # in rad/s11939targetpos.lat += 0.000111940if test_alt:11941targetpos.alt += 511942self.wait_yaw_speed(target_rate, timeout=timeout,11943called_function=lambda plop, empty: send_yaw_rate(11944target_rate, None), minimum_duration=5)11945self.wait_location(11946targetpos,11947accuracy=wp_accuracy,11948timeout=timeout,11949height_accuracy=(2 if test_alt else None),11950)1195111952self.start_subtest("Revert Latitude and invert Yaw rate")11953target_rate = -1.011954targetpos.lat -= 0.000111955if test_alt:11956targetpos.alt -= 511957self.wait_yaw_speed(target_rate, timeout=timeout,11958called_function=lambda plop, empty: send_yaw_rate(11959target_rate, None), minimum_duration=5)11960self.wait_location(11961targetpos,11962accuracy=wp_accuracy,11963timeout=timeout,11964height_accuracy=(2 if test_alt else None),11965)11966self.start_subtest("Changing Yaw rate to zero")11967target_rate = 0.011968self.wait_yaw_speed(target_rate, timeout=timeout,11969called_function=lambda plop, empty: send_yaw_rate(11970target_rate, None), minimum_duration=5)1197111972self.progress("Getting back to home and disarm")11973self.do_RTL(distance_min=0, distance_max=wp_accuracy)11974self.disarm_vehicle()1197511976def SetpointBadVel(self, timeout=30):11977'''try feeding in a very, very bad velocity and make sure it is ignored'''11978self.takeoff(mode='GUIDED')11979# following values from a real log:11980target_speed = Vector3(-3.6019095525029597e+30,119811.7796490496925177e-41,119823.0557017120313744e-26)1198311984self.progress("Feeding in bad global data, hoping we don't move")1198511986def send_speed_vector_global_int(vector , mav_frame):11987self.mav.mav.set_position_target_global_int_send(119880, # timestamp11989self.sysid_thismav(), # target system_id119901, # target component id11991mav_frame,11992MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |11993MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |11994MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |11995MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,119960,119970,119980,11999vector.x, # vx12000vector.y, # vy12001vector.z, # vz120020, # afx120030, # afy120040, # afz120050, # yaw120060, # yawrate12007)12008self.wait_speed_vector(12009Vector3(0, 0, 0),12010timeout=timeout,12011called_function=lambda plop, empty: send_speed_vector_global_int(target_speed, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT), # noqa12012minimum_duration=1012013)1201412015self.progress("Feeding in bad local data, hoping we don't move")1201612017def send_speed_vector_local_ned(vector , mav_frame):12018self.mav.mav.set_position_target_local_ned_send(120190, # timestamp12020self.sysid_thismav(), # target system_id120211, # target component id12022mav_frame,12023MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12024MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12025MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |12026MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,120270,120280,120290,12030vector.x, # vx12031vector.y, # vy12032vector.z, # vz120330, # afx120340, # afy120350, # afz120360, # yaw120370, # yawrate12038)12039self.wait_speed_vector(12040Vector3(0, 0, 0),12041timeout=timeout,12042called_function=lambda plop, empty: send_speed_vector_local_ned(target_speed, mavutil.mavlink.MAV_FRAME_LOCAL_NED), # noqa12043minimum_duration=1012044)1204512046self.do_RTL()1204712048def SetpointGlobalVel(self, timeout=30):12049"""Test set position message in guided mode."""12050# Disable heading and yaw rate test on rover type12051if self.is_rover():12052test_vz = False12053test_heading = False12054test_yaw_rate = False12055else:12056test_vz = True12057test_heading = True12058test_yaw_rate = True1205912060self.install_terrain_handlers_context()1206112062self.set_parameter("FS_GCS_ENABLE", 0)12063self.change_mode("GUIDED")12064self.wait_ready_to_arm()12065self.arm_vehicle()1206612067if self.is_copter() or self.is_heli():12068self.user_takeoff(alt_min=50)1206912070target_speed = Vector3(1.0, 0.0, 0.0)1207112072wp_accuracy = None12073if self.is_copter() or self.is_heli():12074wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)12075wp_accuracy = wp_accuracy * 0.01 # cm to m12076if self.is_plane() or self.is_rover():12077wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)12078if wp_accuracy is None:12079raise ValueError()1208012081def send_speed_vector(vector, mav_frame):12082self.mav.mav.set_position_target_global_int_send(120830, # timestamp12084self.sysid_thismav(), # target system_id120851, # target component id12086mav_frame,12087MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12088MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12089MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |12090MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,120910,120920,120930,12094vector.x, # vx12095vector.y, # vy12096vector.z, # vz120970, # afx120980, # afy120990, # afz121000, # yaw121010, # yawrate12102)1210312104for frame in MAV_FRAMES_TO_TEST:12105frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name12106self.start_subtest("Testing Set Velocity in %s" % frame_name)12107self.progress("Changing Vx speed")12108self.wait_speed_vector(12109target_speed,12110timeout=timeout,12111called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12112minimum_duration=212113)1211412115self.start_subtest("Add Vy speed")12116target_speed.y = 1.012117self.wait_speed_vector(12118target_speed,12119timeout=timeout,12120called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12121minimum_duration=2)1212212123self.start_subtest("Add Vz speed")12124if test_vz:12125target_speed.z = 1.012126else:12127target_speed.z = 0.012128self.wait_speed_vector(12129target_speed,12130timeout=timeout,12131called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12132minimum_duration=212133)1213412135self.start_subtest("Invert Vz speed")12136if test_vz:12137target_speed.z = -1.012138else:12139target_speed.z = 0.012140self.wait_speed_vector(12141target_speed,12142timeout=timeout,12143called_function=lambda plop, empty: send_speed_vector(target_speed, frame), minimum_duration=212144)1214512146self.start_subtest("Invert Vx speed")12147target_speed.x = -1.012148self.wait_speed_vector(12149target_speed,12150timeout=timeout,12151called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12152minimum_duration=212153)1215412155self.start_subtest("Invert Vy speed")12156target_speed.y = -1.012157self.wait_speed_vector(12158target_speed,12159timeout=timeout,12160called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12161minimum_duration=212162)1216312164self.start_subtest("Set Speed to zero")12165target_speed.x = 0.012166target_speed.y = 0.012167target_speed.z = 0.012168self.wait_speed_vector(12169target_speed,12170timeout=timeout,12171called_function=lambda plop, empty: send_speed_vector(target_speed, frame),12172minimum_duration=212173)1217412175if test_heading:12176self.start_subtest("Testing Yaw targeting in %s" % frame_name)1217712178def send_yaw_target(yaw, mav_frame):12179self.mav.mav.set_position_target_global_int_send(121800, # timestamp12181self.sysid_thismav(), # target system_id121821, # target component id12183mav_frame,12184MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12185MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12186MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,121870,121880,121890,121900, # vx121910, # vy121920, # vz121930, # afx121940, # afy121950, # afz12196math.radians(yaw), # yaw121970, # yawrate12198)1219912200target_speed.x = 1.012201target_speed.y = 1.012202if test_vz:12203target_speed.z = -1.012204else:12205target_speed.z = 0.01220612207def send_yaw_target_vel(yaw, vector, mav_frame):12208self.mav.mav.set_position_target_global_int_send(122090, # timestamp12210self.sysid_thismav(), # target system_id122111, # target component id12212mav_frame,12213MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12214MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12215MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,122160,122170,122180,12219vector.x, # vx12220vector.y, # vy12221vector.z, # vz122220, # afx122230, # afy122240, # afz12225math.radians(yaw), # yaw122260, # yawrate12227)1222812229self.start_subtest("Target a fixed Heading")12230target_yaw = 42.012231self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,12232called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))1223312234self.start_subtest("Set target Heading")12235target_yaw = 0.012236self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,12237called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))1223812239self.start_subtest("Add Vx, Vy, Vz speed and target a fixed Heading")12240target_yaw = 42.012241self.wait_heading(12242target_yaw,12243minimum_duration=5,12244timeout=timeout,12245called_function=lambda p, e: send_yaw_target_vel(target_yaw,12246target_speed,12247frame)12248)12249self.wait_speed_vector(12250target_speed,12251called_function=lambda p, e: send_yaw_target_vel(target_yaw,12252target_speed,12253frame)12254)1225512256self.start_subtest("Stop Vx, Vy, Vz speed and target zero Heading")12257target_yaw = 0.012258target_speed.x = 0.012259target_speed.y = 0.012260target_speed.z = 0.012261self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,12262called_function=lambda plop, empty: send_yaw_target_vel(target_yaw, target_speed, frame))12263self.wait_speed_vector(12264target_speed,12265timeout=timeout,12266called_function=lambda p, ee: send_yaw_target_vel(target_yaw,12267target_speed,12268frame),12269minimum_duration=212270)1227112272if test_yaw_rate:12273self.start_subtest("Testing Yaw Rate targeting in %s" % frame_name)1227412275def send_yaw_rate(rate, mav_frame):12276self.mav.mav.set_position_target_global_int_send(122770, # timestamp12278self.sysid_thismav(), # target system_id122791, # target component id12280mav_frame,12281MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12282MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12283MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,122840,122850,122860,122870, # vx122880, # vy122890, # vz122900, # afx122910, # afy122920, # afz122930, # yaw12294rate, # yawrate in rad/s12295)1229612297target_speed.x = 1.012298target_speed.y = 1.012299if test_vz:12300target_speed.z = -1.012301else:12302target_speed.z = 0.01230312304def send_yaw_rate_vel(rate, vector, mav_frame):12305self.mav.mav.set_position_target_global_int_send(123060, # timestamp12307self.sysid_thismav(), # target system_id123081, # target component id12309mav_frame,12310MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |12311MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |12312MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,123130,123140,123150,12316vector.x, # vx12317vector.y, # vy12318vector.z, # vz123190, # afx123200, # afy123210, # afz123220, # yaw12323rate, # yawrate in rad/s12324)1232512326self.start_subtest("Set Yaw rate")12327target_rate = 1.012328self.wait_yaw_speed(target_rate, timeout=timeout,12329called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1233012331self.start_subtest("Invert Yaw rate")12332target_rate = -1.012333self.wait_yaw_speed(target_rate, timeout=timeout,12334called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1233512336self.start_subtest("Stop Yaw rate")12337target_rate = 0.012338self.wait_yaw_speed(target_rate, timeout=timeout,12339called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)1234012341self.start_subtest("Set Yaw Rate and Vx, Vy, Vz speed")12342target_rate = 1.012343self.wait_yaw_speed(12344target_rate,12345called_function=lambda p, e: send_yaw_rate_vel(target_rate,12346target_speed,12347frame),12348minimum_duration=212349)12350self.wait_speed_vector(12351target_speed,12352timeout=timeout,12353called_function=lambda p, e: send_yaw_rate_vel(target_rate,12354target_speed,12355frame),12356minimum_duration=212357)1235812359target_rate = -1.012360target_speed.x = -1.012361target_speed.y = -1.012362if test_vz:12363target_speed.z = 1.012364else:12365target_speed.z = 0.012366self.start_subtest("Invert Vx, Vy, Vz speed")12367self.wait_yaw_speed(12368target_rate,12369timeout=timeout,12370called_function=lambda p, e: send_yaw_rate_vel(target_rate,12371target_speed,12372frame),12373minimum_duration=212374)12375self.wait_speed_vector(12376target_speed,12377timeout=timeout,12378called_function=lambda p, e: send_yaw_rate_vel(target_rate,12379target_speed,12380frame),12381minimum_duration=212382)1238312384target_rate = 0.012385target_speed.x = 0.012386target_speed.y = 0.012387target_speed.z = 0.012388self.start_subtest("Stop Yaw rate and all speed")12389self.wait_yaw_speed(12390target_rate,12391timeout=timeout,12392called_function=lambda p, e: send_yaw_rate_vel(target_rate,12393target_speed,12394frame),12395minimum_duration=212396)12397self.wait_speed_vector(12398target_speed,12399timeout=timeout,12400called_function=lambda p, e: send_yaw_rate_vel(target_rate,12401target_speed,12402frame),12403minimum_duration=212404)1240512406self.progress("Getting back to home and disarm")12407self.do_RTL(distance_min=0, distance_max=wp_accuracy)12408self.disarm_vehicle()1240912410def is_blimp(self):12411return False1241212413def is_copter(self):12414return False1241512416def is_sub(self):12417return False1241812419def is_plane(self):12420return False1242112422def is_rover(self):12423return False1242412425def is_balancebot(self):12426return False1242712428def is_heli(self):12429return False1243012431def is_tracker(self):12432return False1243312434def initial_mode(self):12435'''return mode vehicle should start in with no RC inputs set'''12436return None1243712438def initial_mode_switch_mode(self):12439'''return mode vehicle should start in with default RC inputs set'''12440return None1244112442def upload_fences_from_locations(self, fences, target_system=1, target_component=1):12443seq = 012444items = []1244512446for (vertex_type, locs) in fences:12447if isinstance(locs, dict):12448# circular fence12449item = self.mav.mav.mission_item_int_encode(12450target_system,12451target_component,12452seq, # seq12453mavutil.mavlink.MAV_FRAME_GLOBAL,12454vertex_type,124550, # current124560, # autocontinue12457locs["radius"], # p1124580, # p2124590, # p3124600, # p412461int(locs["loc"].lat * 1e7), # latitude12462int(locs["loc"].lng * 1e7), # longitude1246333.0000, # altitude12464mavutil.mavlink.MAV_MISSION_TYPE_FENCE)12465seq += 112466items.append(item)12467continue12468count = len(locs)12469for loc in locs:12470item = self.mav.mav.mission_item_int_encode(12471target_system,12472target_component,12473seq, # seq12474mavutil.mavlink.MAV_FRAME_GLOBAL,12475vertex_type,124760, # current124770, # autocontinue12478count, # p1124790, # p2124800, # p3124810, # p412482int(loc.lat * 1e7), # latitude12483int(loc.lng * 1e7), # longitude1248433.0000, # altitude12485mavutil.mavlink.MAV_MISSION_TYPE_FENCE)12486seq += 112487items.append(item)1248812489self.check_fence_upload_download(items)1249012491def rally_MISSION_ITEM_INT_from_loc(self, loc):12492return self.create_MISSION_ITEM_INT(12493mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,12494x=int(loc.lat*1e7),12495y=int(loc.lng*1e7),12496z=loc.alt,12497frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,12498mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY12499)1250012501def upload_rally_points_from_locations(self, rally_point_locs):12502'''takes a sequence of locations, sets vehicle rally points to those locations'''12503items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs]12504self.correct_wp_seq_numbers(items)12505self.check_rally_upload_download(items)1250612507def wait_for_initial_mode(self):12508'''wait until we get a heartbeat with an expected initial mode (the12509one specified in the vehicle constructor)'''12510want = self.initial_mode()12511if want is None:12512return12513self.progress("Waiting for initial mode %s" % want)12514self.wait_mode(want)1251512516def wait_for_mode_switch_poll(self):12517'''look for a transition from boot-up-mode (e.g. the flightmode12518specified in Copter's constructor) to the one specified by the mode12519switch value'''12520want = self.initial_mode_switch_mode()12521if want is None:12522return12523self.progress("Waiting for mode-switch mode %s" % want)12524self.wait_mode(want)1252512526def start_subtest(self, description):12527self.progress("-")12528self.progress("---------- %s ----------" % description)12529self.progress("-")1253012531def start_subsubtest(self, description):12532self.progress(".")12533self.progress(".......... %s .........." % description)12534self.progress(".")1253512536def end_subtest(self, description):12537'''TODO: sanity checks?'''12538pass1253912540def end_subsubtest(self, description):12541'''TODO: sanity checks?'''12542pass1254312544def last_onboard_log(self):12545'''return number of last onboard log'''12546mavproxy = self.start_mavproxy()12547mavproxy.send("module load log\n")12548loaded_module = False12549mavproxy.expect(["Loaded module log", "module log already loaded"])12550if mavproxy.match.group(0) == "Loaded module log":12551loaded_module = True12552mavproxy.send("log list\n")12553mavproxy.expect(["lastLog ([0-9]+)", "No logs"])12554if mavproxy.match.group(0) == "No logs":12555num_log = None12556else:12557num_log = int(mavproxy.match.group(1))12558if loaded_module:12559mavproxy.send("module unload log\n")12560mavproxy.expect("Unloaded module log")12561self.stop_mavproxy(mavproxy)12562return num_log1256312564def current_onboard_log_number(self):12565logs = self.download_full_log_list(print_logs=False)12566return sorted(logs.keys())[-1]1256712568def current_onboard_log_filepath(self):12569'''return filepath to currently open dataflash log. We assume that's12570the latest log...'''12571logs = self.log_list()12572latest = logs[-1]12573return latest1257412575def dfreader_for_path(self, path):12576return DFReader.DFReader_binary(path,12577zero_time_base=True)1257812579def dfreader_for_current_onboard_log(self):12580return self.dfreader_for_path(self.current_onboard_log_filepath())1258112582def current_onboard_log_contains_message(self, messagetype):12583self.progress("Checking (%s) for (%s)" %12584(self.current_onboard_log_filepath(), messagetype))12585dfreader = self.dfreader_for_current_onboard_log()12586m = dfreader.recv_match(type=messagetype)12587print("m=%s" % str(m))12588return m is not None1258912590def assert_current_onboard_log_contains_message(self, messagetype):12591if not self.current_onboard_log_contains_message(messagetype):12592raise NotAchievedException("Current onboard log does not contain message %s" % messagetype)1259312594def run_tests(self, tests) -> List[Result]:12595"""Autotest vehicle in SITL."""12596if self.run_tests_called:12597raise ValueError("run_tests called twice")12598self.run_tests_called = True1259912600result_list = []1260112602try:12603self.init()1260412605self.progress("Waiting for a heartbeat with mavlink protocol %s"12606% self.mav.WIRE_PROTOCOL_VERSION)12607self.wait_heartbeat()12608self.wait_for_initial_mode()12609self.progress("Setting up RC parameters")12610self.set_rc_default()12611self.wait_for_mode_switch_poll()12612if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling12613self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)1261412615for test in tests:12616self.drain_mav_unparsed()12617result_list.append(self.run_one_test(test))1261812619except pexpect.TIMEOUT:12620self.progress("Failed with timeout")12621result = Result(test)12622result.passed = False12623result.reason = "Failed with timeout"12624result_list.append(result)12625if self.logs_dir:12626if glob.glob("core*") or glob.glob("ap-*.core"):12627self.check_logs("FRAMEWORK")1262812629if self.rc_thread is not None:12630self.progress("Joining RC thread")12631self.rc_thread_should_quit = True12632self.rc_thread.join()12633self.rc_thread = None1263412635if self.mav is not None:12636self.mav.close()12637self.mav = None1263812639self.stop_SITL()1264012641valgrind_log = util.valgrind_log_filepath(binary=self.binary,12642model=self.frame)12643files = glob.glob("*" + valgrind_log)12644valgrind_failed = False12645for valgrind_log in files:12646os.chmod(valgrind_log, 0o644)12647if os.path.getsize(valgrind_log) > 0:12648target = self.buildlogs_path("%s-%s" % (12649self.log_name(),12650os.path.basename(valgrind_log)))12651self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target))12652shutil.move(valgrind_log, target)12653valgrind_failed = True12654if valgrind_failed:12655result_list.append(ValgrindFailedResult())1265612657return result_list1265812659def dictdiff(self, dict1, dict2):12660fred = copy.copy(dict1)12661for key in dict2.keys():12662try:12663del fred[key]12664except KeyError:12665pass12666return fred1266712668# download parameters tries to cope with its download being12669# interrupted or broken by simply retrying the download a few12670# times.12671def download_parameters(self, target_system, target_component):12672# try a simple fetch-all:12673last_parameter_received = 012674attempt_count = 012675start_done = False12676# make flake8 happy:12677count = 012678expected_count = 012679seen_ids = {}12680self.progress("Downloading parameters")12681debug = False12682while True:12683now = self.get_sim_time_cached()12684if not start_done or now - last_parameter_received > 10:12685start_done = True12686if attempt_count > 3:12687raise AutoTestTimeoutException("Failed to download parameters (have %s/%s) (seen_ids-count=%u)" %12688(str(count), str(expected_count), len(seen_ids.keys())))12689elif attempt_count != 0:12690self.progress("Download failed; retrying")12691self.delay_sim_time(1)12692debug = True12693self.drain_mav()12694self.mav.mav.param_request_list_send(target_system, target_component)12695attempt_count += 112696count = 012697expected_count = None12698seen_ids = {}12699id_seq = {}12700m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=10)12701if m is None:12702raise AutoTestTimeoutException("tardy PARAM_VALUE (have %s/%s)" % (12703str(count), str(expected_count)))12704if m.param_index == 65535:12705self.progress("volunteered parameter: %s" % str(m))12706continue12707if debug:12708self.progress(" received id=%4u param_count=%4u %s=%f" %12709(m.param_index, m.param_count, m.param_id, m.param_value))12710if m.param_index >= m.param_count:12711raise ValueError("parameter index (%u) gte parameter count (%u)" %12712(m.param_index, m.param_count))12713if expected_count is None:12714expected_count = m.param_count12715else:12716if m.param_count != expected_count:12717raise ValueError("expected count changed")12718if m.param_id not in seen_ids:12719count += 112720seen_ids[m.param_id] = m.param_value12721last_parameter_received = now12722if count == expected_count:12723break1272412725self.progress("Downloaded %u parameters OK (attempt=%u)" %12726(count, attempt_count))12727return (seen_ids, id_seq)1272812729def test_parameters_download(self):12730self.start_subtest("parameter download")12731target_system = self.sysid_thismav()12732target_component = 112733self.progress("First Download:")12734(parameters, seq_id) = self.download_parameters(target_system, target_component)12735self.reboot_sitl()12736self.progress("Second download:")12737(parameters2, seq2_id) = self.download_parameters(target_system, target_component)1273812739delta = self.dictdiff(parameters, parameters2)12740if len(delta) != 0:12741raise ValueError("Got %u fewer parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %12742(len(delta), len(parameters), len(parameters2), str(delta.keys())))1274312744delta = self.dictdiff(parameters2, parameters)12745if len(delta) != 0:12746raise ValueError("Got %u extra parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %12747(len(delta), len(parameters), len(parameters2), str(delta.keys())))1274812749self.end_subsubtest("parameter download")1275012751def test_enable_parameter(self):12752self.start_subtest("enable parameters")12753target_system = 112754target_component = 112755parameters = self.download_parameters(target_system, target_component)12756enable_parameter = self.sample_enable_parameter()12757if enable_parameter is None:12758self.progress("Skipping enable parameter check as no enable parameter supplied")12759return12760self.set_parameter(enable_parameter, 1)12761parameters2 = self.download_parameters(target_system, target_component)12762if len(parameters) == len(parameters2):12763raise NotAchievedException("Enable parameter did not increase no of parameters downloaded")12764self.end_subsubtest("enable download")1276512766def test_parameters_mis_total(self):12767self.start_subsubtest("parameter mis_total")12768if self.is_tracker():12769# uses CMD_TOTAL not MIS_TOTAL, and it's in a scalr not a12770# group and it's generally all bad.12771return12772self.start_subtest("Ensure GCS is not able to set MIS_TOTAL")12773old_mt = self.get_parameter("MIS_TOTAL", attempts=20) # retries to avoid seeming race condition with MAVProxy12774ex = None12775try:12776self.set_parameter("MIS_TOTAL", 17, attempts=1)12777except ValueError as e:12778ex = e12779if ex is None:12780raise NotAchievedException("Set parameter when I shouldn't have")12781if old_mt != self.get_parameter("MIS_TOTAL"):12782raise NotAchievedException("Total has changed")1278312784self.start_subtest("Ensure GCS is able to set other MIS_ parameters")12785self.set_parameter("MIS_OPTIONS", 1)12786if self.get_parameter("MIS_OPTIONS") != 1:12787raise NotAchievedException("Failed to set MIS_OPTIONS")1278812789mavproxy = self.start_mavproxy()12790from_mavproxy = self.get_parameter_mavproxy(mavproxy, "MIS_OPTIONS")12791if from_mavproxy != 1:12792raise NotAchievedException("MAVProxy failed to get parameter")12793self.stop_mavproxy(mavproxy)1279412795def test_parameter_documentation(self):12796'''ensure parameter documentation is valid'''12797self.start_subsubtest("Check all parameters are documented")12798self.test_parameter_documentation_get_all_parameters()1279912800def Parameters(self):12801'''general small tests for parameter system'''12802if self.is_balancebot():12803# same binary and parameters as Rover12804return12805self.test_parameter_documentation()12806self.test_parameters_mis_total()12807self.test_parameters_download()1280812809def disabled_tests(self):12810return {}1281112812def test_parameter_checks_poscontrol(self, param_prefix):12813self.wait_ready_to_arm()12814self.context_push()12815self.set_parameter("%s_NE_POS_P" % param_prefix, -1)12816self.run_cmd(12817mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,12818p1=1, # ARM12819timeout=4,12820want_result=mavutil.mavlink.MAV_RESULT_FAILED,12821)12822self.context_pop()12823self.run_cmd(12824mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,12825p1=1, # ARM12826timeout=4,12827want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,12828)12829self.disarm_vehicle()1283012831def assert_not_receiving_message(self, message, timeout=1, mav=None):12832self.progress("making sure we're not getting %s messages" % message)12833if mav is None:12834mav = self.mav12835m = mav.recv_match(type=message, blocking=True, timeout=timeout)12836if m is not None:12837raise PreconditionFailedException("Receiving %s messages" % message)1283812839def PIDTuning(self):12840'''Test PID Tuning'''12841self.assert_not_receiving_message('PID_TUNING', timeout=5)12842self.set_parameter("GCS_PID_MASK", 1)12843self.progress("making sure we are now getting PID_TUNING messages")12844self.assert_receive_message('PID_TUNING', timeout=5)1284512846def sample_mission_filename(self):12847return "flaps.txt"1284812849def AdvancedFailsafe(self):12850'''Test Advanced Failsafe'''12851ex = None12852try:12853self.drain_mav()12854if self.is_plane(): # other vehicles can always terminate12855self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)12856self.set_parameters({12857"AFS_ENABLE": 1,12858"MAV_GCS_SYSID": self.mav.source_system,12859"RTL_AUTOLAND": 2,12860})12861self.drain_mav()12862self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)12863self.set_parameter("AFS_TERM_ACTION", 42)12864self.load_sample_mission()12865self.context_collect("STATUSTEXT")12866self.change_mode("AUTO") # must go to auto for AFS to latch on12867self.wait_statustext("AFS State: AFS_AUTO", check_context=True)12868if self.is_plane():12869self.change_mode("MANUAL")12870elif self.is_copter():12871self.change_mode("STABILIZE")1287212873self.start_subtest("RC Failure")12874self.context_push()12875self.context_collect("STATUSTEXT")12876self.set_parameters({12877"AFS_RC_FAIL_TIME": 1,12878"SIM_RC_FAIL": 1,12879})12880self.wait_statustext("Terminating due to RC failure", check_context=True)12881self.context_pop()12882self.set_parameter("AFS_TERMINATE", 0)1288312884if not self.is_plane():12885# plane requires a polygon fence...12886self.start_subtest("Altitude Limit breach")12887self.set_parameters({12888"AFS_AMSL_LIMIT": 100,12889"AFS_QNH_PRESSURE": 1015.2,12890})12891self.do_fence_enable()12892self.wait_statustext("Terminating due to fence breach", check_context=True)12893self.set_parameter("AFS_AMSL_LIMIT", 0)12894self.set_parameter("AFS_TERMINATE", 0)12895self.do_fence_disable()1289612897self.start_subtest("GPS Failure")12898self.wait_ready_to_arm()12899self.context_push()12900self.context_collect("STATUSTEXT")12901self.set_parameters({12902"AFS_MAX_GPS_LOSS": 1,12903"SIM_GPS1_ENABLE": 0,12904})12905self.wait_statustext("AFS State: GPS_LOSS", check_context=True)12906self.context_pop()12907self.set_parameter("AFS_TERMINATE", 0)1290812909self.start_subtest("GCS Request")12910self.context_push()12911self.context_collect("STATUSTEXT")12912self.run_cmd(12913mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,12914p1=1, # terminate12915)12916self.wait_statustext("Terminating due to GCS request", check_context=True)12917self.context_pop()12918self.set_parameter("AFS_TERMINATE", 0)1291912920except Exception as e:12921ex = e12922try:12923self.do_fence_disable()12924except ValueError:12925# may not actually be enabled....12926pass12927if ex is not None:12928raise ex1292912930def AdvancedFailsafeBadBaro(self):12931'''ensure GPS can be used as a fallback in case of baro dying'''12932self.set_parameters({12933"AFS_ENABLE": 1,12934"MAV_GCS_SYSID": self.mav.source_system,12935"AFS_AMSL_LIMIT": 1000,12936"AFS_QNH_PRESSURE": 1000,12937"AFS_AMSL_ERR_GPS": 10,12938})12939self.wait_ready_to_arm()12940self.start_subtest("Ensuring breaking baros doesn't terminate")12941self.set_parameters({12942"SIM_BARO_DISABLE": 1,12943"SIM_BAR2_DISABLE": 1,12944})12945self.delay_sim_time(10)12946self.start_subtest("Ensuring breaking GPS does now terminate")12947self.set_parameters({12948"SIM_GPS1_ENABLE": 0,12949})12950self.wait_statustext("Terminating due to fence breach")1295112952def drain_mav_seconds(self, seconds):12953tstart = self.get_sim_time_cached()12954while self.get_sim_time_cached() - tstart < seconds:12955self.drain_mav()12956self.delay_sim_time(0.5)1295712958def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT", verbose=False):12959tstart = self.get_sim_time()12960while True:12961now = self.get_sim_time_cached()12962if now - tstart > timeout:12963raise AutoTestTimeoutException("Did not get good GPS lock")12964m = self.mav.recv_match(type=message_type, blocking=True, timeout=0.1)12965if verbose:12966self.progress("Received: %s" % str(m))12967if m is None:12968continue12969if m.fix_type >= fix_type:12970break1297112972def NMEAOutput(self):12973'''Test AHRS NMEA Output can be read by out NMEA GPS'''12974self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output12975self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA12976port = self.spare_network_port()12977self.customise_SITL_commandline([12978"--serial4=tcp:%u" % port, # GPS2 is NMEA....12979"--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port12980])12981self.do_timesync_roundtrip()12982self.wait_gps_fix_type_gte(3)12983gps1 = self.assert_receive_message("GPS_RAW_INT", timeout=10, verbose=True)12984tstart = self.get_sim_time()12985while True:12986now = self.get_sim_time_cached()12987if now - tstart > 20:12988raise NotAchievedException("NMEA output not updating?!")12989gps2 = self.mav.recv_match(type="GPS2_RAW", blocking=True, timeout=1)12990self.progress("gps2=%s" % str(gps2))12991if gps2 is None:12992continue12993if gps2.time_usec != 0:12994break12995max_distance = 112996distance = self.get_distance_int(gps1, gps2)12997if distance > max_distance:12998raise NotAchievedException("NMEA output inaccurate (dist=%f want<%f)" %12999(distance, max_distance))1300013001def mavproxy_load_module(self, mavproxy, module):13002mavproxy.send("module load %s\n" % module)13003mavproxy.expect("Loaded module %s" % module)1300413005def mavproxy_unload_module(self, mavproxy, module):13006mavproxy.send("module unload %s\n" % module)13007mavproxy.expect("Unloaded module %s" % module)1300813009def AccelCal(self):13010'''Accelerometer Calibration testing'''13011ex = None13012mavproxy = self.start_mavproxy()13013try:13014# setup with pre-existing accel offsets, to show that existing offsets don't13015# adversely affect a new cal13016pre_aofs = [Vector3(2.8, 1.2, 1.7),13017Vector3(0.2, -0.9, 2.9)]13018pre_ascale = [Vector3(0.95, 1.2, 0.98),13019Vector3(1.1, 1.0, 0.93)]13020aofs = [Vector3(0.7, -0.3, 1.8),13021Vector3(-2.1, 1.9, 2.3)]13022ascale = [Vector3(0.98, 1.12, 1.05),13023Vector3(1.11, 0.98, 0.96)]13024atrim = Vector3(0.05, -0.03, 0)13025pre_atrim = Vector3(-0.02, 0.04, 0)13026param_map = [("INS_ACCOFFS", "SIM_ACC1_BIAS", pre_aofs[0], aofs[0]),13027("INS_ACC2OFFS", "SIM_ACC2_BIAS", pre_aofs[1], aofs[1]),13028("INS_ACCSCAL", "SIM_ACC1_SCAL", pre_ascale[0], ascale[0]),13029("INS_ACC2SCAL", "SIM_ACC2_SCAL", pre_ascale[1], ascale[1]),13030("AHRS_TRIM", "SIM_ACC_TRIM", pre_atrim, atrim)]13031axes = ['X', 'Y', 'Z']1303213033# form the pre-calibration params13034initial_params = {}13035for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:13036for axis in axes:13037initial_params[ins_prefix + "_" + axis] = getattr(pre_value, axis.lower())13038initial_params[sim_prefix + "_" + axis] = getattr(post_value, axis.lower())13039self.set_parameters(initial_params)13040self.customise_SITL_commandline(["-M", "calibration"])13041self.mavproxy_load_module(mavproxy, "sitl_calibration")13042self.mavproxy_load_module(mavproxy, "calibration")13043self.mavproxy_load_module(mavproxy, "relay")13044mavproxy.send("sitl_accelcal\n")13045mavproxy.send("accelcal\n")13046mavproxy.expect("Calibrated")13047for wanted in [13048"level",13049"on its LEFT side",13050"on its RIGHT side",13051"nose DOWN",13052"nose UP",13053"on its BACK",13054]:13055timeout = 213056mavproxy.expect("Place vehicle %s and press any key." % wanted, timeout=timeout)13057mavproxy.expect("sitl_accelcal: sending attitude, please wait..", timeout=timeout)13058mavproxy.expect("sitl_accelcal: attitude detected, please press any key..", timeout=timeout)13059mavproxy.send("\n")13060mavproxy.expect(".*Calibration successful", timeout=timeout)13061self.drain_mav()1306213063self.progress("Checking results")13064accuracy_pct = 0.513065for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:13066for axis in axes:13067pname = ins_prefix+"_"+axis13068v = self.get_parameter(pname)13069expected_v = getattr(post_value, axis.lower())13070if v == expected_v:13071continue13072error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)13073if error_pct > accuracy_pct:13074raise NotAchievedException(13075"Incorrect value %.6f for %s should be %.6f error %.2f%%" %13076(v, pname, expected_v, error_pct))13077else:13078self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct))13079except Exception as e:13080self.print_exception_caught(e)13081ex = e13082self.mavproxy_unload_module(mavproxy, "relay")13083self.mavproxy_unload_module(mavproxy, "calibration")13084self.mavproxy_unload_module(mavproxy, "sitl_calibration")13085self.stop_mavproxy(mavproxy)13086if ex is not None:13087raise ex1308813089def ahrstrim_preflight_cal(self):13090# setup with non-zero accel offsets13091self.set_parameters({13092"INS_ACCOFFS_X": 0.7,13093"INS_ACCOFFS_Y": -0.3,13094"INS_ACCOFFS_Z": 1.8,13095"INS_ACC2OFFS_X": -2.1,13096"INS_ACC2OFFS_Y": 1.9,13097"INS_ACC2OFFS_Z": 2.3,13098"SIM_ACC1_BIAS_X": 0.7,13099"SIM_ACC1_BIAS_Y": -0.3,13100"SIM_ACC1_BIAS_Z": 1.8,13101"SIM_ACC2_BIAS_X": -2.1,13102"SIM_ACC2_BIAS_Y": 1.9,13103"SIM_ACC2_BIAS_Z": 2.3,13104"AHRS_TRIM_X": 0.05,13105"AHRS_TRIM_Y": -0.03,13106"SIM_ACC_TRIM_X": -0.04,13107"SIM_ACC_TRIM_Y": 0.05,13108})13109expected_parms = {13110"AHRS_TRIM_X": -0.04,13111"AHRS_TRIM_Y": 0.05,13112}1311313114self.progress("Starting ahrstrim")13115self.drain_mav()13116self.mav.mav.command_long_send(self.sysid_thismav(), 1,13117mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,131180, 0, 0, 0, 2, 0, 0)13119self.wait_statustext('Trim OK')13120self.drain_mav()1312113122self.progress("Checking results")13123accuracy_pct = 0.213124for (pname, expected_v) in expected_parms.items():13125v = self.get_parameter(pname)13126if v == expected_v:13127continue13128error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)13129if error_pct > accuracy_pct:13130raise NotAchievedException(13131"Incorrect value %.6f for %s should be %.6f error %.2f%%" %13132(v, pname, expected_v, error_pct))13133self.progress("Correct value %.4f for %s error %.2f%%" %13134(v, pname, error_pct))1313513136def user_takeoff(self, alt_min=30, timeout=30, max_err=5):13137'''takeoff using mavlink takeoff command'''13138self.run_cmd(13139mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,13140p7=alt_min, # param713141)13142self.wait_altitude(alt_min - 1,13143(alt_min + max_err),13144relative=True,13145timeout=timeout)1314613147def ahrstrim_attitude_correctness(self):13148self.wait_ready_to_arm()13149HOME = self.sitl_start_location()13150for heading in 0, 90:13151self.customise_SITL_commandline([13152"--home", "%s,%s,%s,%s" % (HOME.lat, HOME.lng, HOME.alt, heading)13153])13154for ahrs_type in [0, 2, 3, 11]:13155self.start_subsubtest("Testing AHRS_TYPE=%u" % ahrs_type)13156self.context_push()1315713158# Special setup for ExternalAHRS (type 11)13159if ahrs_type == 11:13160# Test all simulated ExternalAHRS backends13161external_ahrs_configs = [13162{13163"name": "VectorNav",13164"device": "VectorNav",13165"eahrs_type": 1,13166},13167{13168"name": "MicroStrain5",13169"device": "MicroStrain5",13170"eahrs_type": 2,13171},13172{13173"name": "InertialLabs",13174"device": "ILabs",13175"eahrs_type": 5,13176},13177{13178"name": "MicroStrain7",13179"device": "MicroStrain7",13180"eahrs_type": 7,13181},13182]1318313184for config in external_ahrs_configs:13185self.start_subsubtest("Testing ExternalAHRS backend: %s" % config["name"])13186self.context_push()1318713188self.customise_SITL_commandline([13189"--serial4=sim:%s" % config["device"],13190])13191self.set_parameters({13192"EAHRS_TYPE": config["eahrs_type"],13193"SERIAL4_PROTOCOL": 36, # ExternalAHRS protocol13194"SERIAL4_BAUD": 230400,13195"GPS1_TYPE": 21, # External AHRS13196"AHRS_EKF_TYPE": ahrs_type,13197"INS_GYR_CAL": 1,13198"EAHRS_SENSORS": 0xD, # GPS|BARO|COMPASS (exclude IMU)13199})13200self.reboot_sitl()13201self.delay_sim_time(5)13202self.progress("Running accelcal")13203self.run_cmd(13204mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,13205p5=4,13206timeout=5,13207)13208self.wait_prearm_sys_status_healthy(timeout=120)1320913210for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:13211self.set_parameters({13212'AHRS_TRIM_X': math.radians(r),13213'AHRS_TRIM_Y': math.radians(p),13214"SIM_ACC_TRIM_X": math.radians(r),13215"SIM_ACC_TRIM_Y": math.radians(p),13216})13217self.reboot_sitl()13218self.context_set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SIM_STATE, 10)13219att_desroll = 013220att_despitch = 013221if ahrs_type == 11:13222# this is very nasty compatibility13223# code for the fact our rotations are13224# incorrect for ExternalAHRS eulers13225# and rotation matrix! It is here to13226# ensure behaviour is preserved until13227# we can fix the bug! Search for13228# "note that this is suspect" to find13229# the problem code.13230att_desroll = -r13231att_despitch = -p13232self.wait_attitude(desroll=att_desroll, despitch=att_despitch, timeout=120, tolerance=1.5)13233if ahrs_type != 0:13234self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)13235self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)13236self.wait_attitude(desroll=0, despitch=0, message_type='SIM_STATE', tolerance=1, timeout=120)1323713238self.context_pop()13239self.reboot_sitl()1324013241# Skip the normal test loop for ahrs_type 11 since we already tested it above13242self.context_pop()13243continue13244else:13245self.set_parameter("AHRS_EKF_TYPE", ahrs_type)13246self.reboot_sitl()13247self.wait_prearm_sys_status_healthy(timeout=120)13248for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:13249self.set_parameters({13250'AHRS_TRIM_X': math.radians(r),13251'AHRS_TRIM_Y': math.radians(p),13252"SIM_ACC_TRIM_X": math.radians(r),13253"SIM_ACC_TRIM_Y": math.radians(p),13254})13255self.reboot_sitl()13256self.context_set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SIM_STATE, 10)13257self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5)13258self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5, message_type='SIM_STATE')13259if ahrs_type != 0: # we don't get secondary msgs while DCM is primary13260self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)13261self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)13262self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120, message_type='SIM_STATE')1326313264self.context_pop()13265self.reboot_sitl()1326613267def AHRSTrim(self):13268'''AHRS trim testing'''13269self.start_subtest("Attitude Correctness")13270self.ahrstrim_attitude_correctness()13271self.delay_sim_time(5)13272self.start_subtest("Preflight Calibration")13273self.ahrstrim_preflight_cal()1327413275def Button(self):13276'''Test Buttons'''13277self.set_parameter("SIM_PIN_MASK", 0)13278self.set_parameter("BTN_ENABLE", 1)13279self.drain_mav()13280self.do_heartbeats(force=True)13281btn = 413282pin = 313283self.set_parameter("BTN_PIN%u" % btn, pin, verbose=True)13284m = self.assert_not_receive_message('BUTTON_CHANGE')13285mask = 1 << pin13286self.set_parameter("SIM_PIN_MASK", mask)13287m = self.assert_receive_message('BUTTON_CHANGE', verbose=True)13288if not (m.state & mask):13289raise NotAchievedException("Bit not set in mask (got=%u want=%u)" % (m.state, mask))13290m2 = self.assert_receive_message('BUTTON_CHANGE', timeout=10)13291self.progress("### m2: %s" % str(m2))13292# wait for messages to stop coming:13293self.drain_mav_seconds(15)1329413295new_mask = 013296self.send_set_parameter("SIM_PIN_MASK", new_mask, verbose=True)13297m3 = self.assert_receive_message('BUTTON_CHANGE')13298self.progress("### m3: %s" % str(m3))1329913300if m.last_change_ms == m3.last_change_ms:13301raise NotAchievedException("last_change_ms same as first message")13302if m3.state != new_mask:13303raise NotAchievedException("Unexpected mask (want=%u got=%u)" %13304(new_mask, m3.state))13305self.progress("correct BUTTON_CHANGE event received")1330613307if self.is_tracker():13308# tracker starts armed, which is annoying13309self.progress("Skipping arm/disarm tests for tracker")13310return1331113312self.context_push()13313self.wait_ready_to_arm()13314self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM13315self.set_parameter("SIM_PIN_MASK", mask)13316self.wait_armed()13317self.set_parameter("SIM_PIN_MASK", 0)13318self.wait_disarmed()13319self.context_pop()1332013321if self.is_rover():13322self.context_push()13323# arming should be inhibited while e-STOP is in use:13324# set the function:13325self.set_parameter("BTN_FUNC%u" % btn, 31)13326# invert the sense of the pin, so eStop is asserted when pin is low:13327self.set_parameter("BTN_OPTIONS%u" % btn, 1 << 1)13328self.reboot_sitl()13329# assert the pin:13330self.set_parameter("SIM_PIN_MASK", mask)13331self.wait_ready_to_arm()13332self.arm_vehicle()13333self.disarm_vehicle()13334# de-assert the pin:13335self.set_parameter("SIM_PIN_MASK", 0)13336self.delay_sim_time(1) # 5Hz update rate on Button library13337self.context_collect("STATUSTEXT")13338# try to arm the vehicle:13339self.run_cmd(13340mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,13341p1=1, # ARM13342want_result=mavutil.mavlink.MAV_RESULT_FAILED,13343)13344self.assert_prearm_failure("Motors Emergency Stopped",13345other_prearm_failures_fatal=False)13346self.reboot_sitl()13347self.assert_prearm_failure(13348"Motors Emergency Stopped",13349other_prearm_failures_fatal=False)13350self.context_pop()13351self.reboot_sitl()1335213353if self.is_rover():13354self.start_subtest("Testing using buttons for changing modes")13355self.context_push()13356if not self.mode_is('MANUAL'):13357raise NotAchievedException("Bad mode")13358self.set_parameter("BTN_FUNC%u" % btn, 53) # steering mode13359# press button:13360self.set_parameter("SIM_PIN_MASK", mask)13361self.wait_mode('STEERING')13362# release button:13363self.set_parameter("SIM_PIN_MASK", 0)13364self.wait_mode('MANUAL')13365self.context_pop()1336613367def compare_number_percent(self, num1, num2, percent):13368if num1 == 0 and num2 == 0:13369return True13370if abs(num1 - num2) / max(abs(num1), abs(num2)) <= percent * 0.01:13371return True13372return False1337313374def bit_extract(self, number, offset, length):13375mask = 013376for i in range(offset, offset+length):13377mask |= 1 << i13378return (number & mask) >> offset1337913380def tf_encode_gps_latitude(self, lat):13381value = 013382if lat < 0:13383value = ((abs(lat)//100)*6) | 0x4000000013384else:13385value = ((abs(lat)//100)*6)13386return value1338713388def tf_validate_gps(self, value): # shared by proto 4 and proto 1013389self.progress("validating gps (0x%02x)" % value)13390lat = value13391gri = self.assert_receive_message('GPS_RAW_INT')13392gri_lat = self.tf_encode_gps_latitude(gri.lat)13393self.progress("GLOBAL_POSITION_INT lat==%f frsky==%f" % (gri_lat, lat))13394if gri_lat == lat:13395return True13396return False1339713398def tfp_prep_number(self, number, digits, power):13399res = 013400abs_number = abs(number)13401if digits == 2 and power == 1: # number encoded on 8 bits: 7 bits for digits + 1 for 10^power13402if abs_number < 100:13403res = abs_number << 113404elif abs_number < 1270:13405res = (round(abs_number * 0.1) << 1) | 0x113406else: # transmit max possible value (0x7F x 10^1 = 1270)13407res = 0xFF13408if number < 0: # if number is negative, add sign bit in front13409res |= 0x1 << 813410elif digits == 2 and power == 2: # number encoded on 9 bits: 7 bits for digits + 2 for 10^power13411if abs_number < 100:13412res = abs_number << 213413elif abs_number < 1000:13414res = (round(abs_number * 0.1) << 2) | 0x113415elif abs_number < 10000:13416res = (round(abs_number * 0.01) << 2) | 0x213417elif abs_number < 127000:13418res = (round(abs_number * 0.001) << 2) | 0x313419else: # transmit max possible value (0x7F x 10^3 = 127000)13420res = 0x1FF13421if number < 0: # if number is negative, add sign bit in front13422res |= 0x1 << 913423elif digits == 3 and power == 1: # number encoded on 11 bits: 10 bits for digits + 1 for 10^power13424if abs_number < 1000:13425res = abs_number << 113426elif abs_number < 10240:13427res = (round(abs_number * 0.1) << 1) | 0x113428else: # transmit max possible value (0x3FF x 10^1 = 10240)13429res = 0x7FF13430if number < 0: # if number is negative, add sign bit in front13431res |= 0x1 << 1113432elif digits == 3 and power == 2: # number encoded on 12 bits: 10 bits for digits + 2 for 10^power13433if abs_number < 1000:13434res = abs_number << 213435elif abs_number < 10000:13436res = (round(abs_number * 0.1) << 2) | 0x113437elif abs_number < 100000:13438res = (round(abs_number * 0.01) << 2) | 0x213439elif abs_number < 1024000:13440res = (round(abs_number * 0.001) << 2) | 0x313441else: # transmit max possible value (0x3FF x 10^3 = 127000)13442res = 0xFFF13443if number < 0: # if number is negative, add sign bit in front13444res |= 0x1 << 1213445return res1344613447def tfp_validate_ap_status(self, value): # 0x500113448self.progress("validating ap_status(0x%02x)" % value)13449flight_mode = self.bit_extract(value, 0, 5) - 1 # first mode is 1 not 0 :-)13450# simple_mode = self.bit_extract(value, 5, 2)13451# is_flying = not self.bit_extract(value, 7, 1)13452# status_armed = self.bit_extract(value, 8, 1)13453# batt_failsafe = self.bit_extract(value, 9, 1)13454# ekf_failsafe = self.bit_extract(value, 10, 2)13455# imu_temp = self.bit_extract(value, 26, 6) + 19 # IMU temperature: 0 means temp =< 19, 63 means temp => 8213456heartbeat = self.wait_heartbeat()13457mav_flight_mode = heartbeat.custom_mode13458self.progress(" mode=%u heartbeat=%u" % (flight_mode, mav_flight_mode))13459if mav_flight_mode == flight_mode:13460self.progress("flight mode match")13461return True13462# FIXME: need to check other values as well13463return False1346413465def tfp_validate_attitude(self, value):13466self.progress("validating attitude(0x%02x)" % value)13467roll = (min(self.bit_extract(value, 0, 11), 1800) - 900) * 0.2 # roll [0,1800] ==> [-180,180]13468pitch = (min(self.bit_extract(value, 11, 10), 900) - 450) * 0.2 # pitch [0,900] ==> [-90,90]13469# rng_cm = self.bit_extract(value, 22, 10) * (10 ^ self.bit_extract(value, 21, 1)) # cm13470atti = self.assert_receive_message('ATTITUDE')13471atti_roll = round(atti.roll)13472self.progress("ATTITUDE roll==%f frsky==%f" % (atti_roll, roll))13473if abs(atti_roll - roll) >= 5:13474return False13475atti_pitch = round(atti.pitch)13476self.progress("ATTITUDE pitch==%f frsky==%f" % (atti_pitch, pitch))13477if abs(atti_pitch - pitch) >= 5:13478return False13479# FIXME: need to check other values as well13480return True1348113482def tfp_validate_home_status(self, value):13483self.progress("validating home status(0x%02x)" % value)13484# home_dist_m = self.bit_extract(value,2,10) * (10^self.bit_extract(value,0,2))13485home_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) # noqa13486# home_angle_d = self.bit_extract(value, 25, 7) * 313487gpi = self.assert_receive_message('GLOBAL_POSITION_INT')13488gpi_relative_alt_dm = gpi.relative_alt/100.013489self.progress("GLOBAL_POSITION_INT rel_alt==%fm frsky_home_alt==%fm" % (gpi_relative_alt_dm, home_alt_dm))13490if abs(gpi_relative_alt_dm - home_alt_dm) < 10:13491return True13492# FIXME: need to check other values as well13493return False1349413495def tfp_validate_gps_status(self, value):13496self.progress("validating gps status(0x%02x)" % value)13497# num_sats = self.bit_extract(value, 0, 4)13498gps_status = self.bit_extract(value, 4, 2) + self.bit_extract(value, 14, 2)13499# gps_hdop = self.bit_extract(value, 7, 7) * (10 ^ self.bit_extract(value, 6, 1)) # dm13500# 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 # noqa13501gri = self.assert_receive_message('GPS_RAW_INT')13502gri_status = gri.fix_type13503self.progress("GPS_RAW_INT fix_type==%f frsky==%f" % (gri_status, gps_status))13504if gps_status == gri_status:13505return True13506# FIXME: need to check other values as well13507return False1350813509def tfp_validate_vel_and_yaw(self, value): # 0x500513510self.progress("validating vel_and_yaw(0x%02x)" % value)13511z_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) # noqa13512xy_vel = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))13513yaw = self.bit_extract(value, 17, 11) * 0.213514gpi = self.mav.recv_match(13515type='GLOBAL_POSITION_INT',13516blocking=True,13517timeout=113518)13519if gpi is None:13520return13521self.progress(" yaw=%u gpi=%u" % (yaw, gpi.hdg*0.01))13522self.progress(" xy_vel=%u" % xy_vel)13523self.progress(" z_vel_dm_per_second=%u" % z_vel_dm_per_second)13524if self.compare_number_percent(gpi.hdg*0.01, yaw, 10):13525self.progress("Yaw match")13526return True13527# FIXME: need to be under way to check the velocities, really....13528return False1352913530def tfp_validate_battery1(self, value):13531self.progress("validating battery1 (0x%02x)" % value)13532voltage = self.bit_extract(value, 0, 9) # dV13533# current = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))13534# mah = self.bit_extract(value, 17, 15)13535voltage = value * 0.113536batt = self.assert_receive_message(13537'BATTERY_STATUS',13538timeout=5,13539condition="BATTERY_STATUS.id==0"13540)13541battery_status_value = batt.voltages[0]*0.00113542self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_value, voltage))13543if abs(battery_status_value - voltage) > 0.1:13544return False13545# FIXME: need to check other values as well13546return True1354713548def tfp_validate_params(self, value):13549param_id = self.bit_extract(value, 24, 4)13550param_value = self.bit_extract(value, 0, 24)13551self.progress("received param (0x%02x) (id=%u value=%u)" %13552(value, param_id, param_value))13553frame_type = param_value13554hb = self.mav.messages['HEARTBEAT']13555hb_type = hb.type13556self.progress("validate_params: HEARTBEAT type==%f frsky==%f param_id=%u" % (hb_type, frame_type, param_id))13557if param_id != 1:13558return False13559if hb_type == frame_type:13560return True13561# FIXME: need to check other values as well13562return False1356313564def tfp_validate_rpm(self, value):13565self.progress("validating rpm (0x%02x)" % value)13566tf_rpm = self.bit_extract(value, 0, 16)13567rpm = self.assert_receive_message(type='RPM', timeout=5)13568rpm_value = round(rpm.rpm1 * 0.1)13569self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tf_rpm))13570if rpm_value != tf_rpm:13571return False13572return True1357313574def tfp_validate_terrain(self, value):13575self.progress("validating terrain(0x%02x)" % value)13576alt_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) # noqa13577terrain = self.assert_receive_message('TERRAIN_REPORT')13578altitude_terrain_dm = round(terrain.current_height*10)13579self.progress("TERRAIN_REPORT terrain_alt==%fdm frsky_terrain_alt==%fdm" % (altitude_terrain_dm, alt_above_terrain_dm))13580if abs(altitude_terrain_dm - alt_above_terrain_dm) < 1:13581return True13582return False1358313584def tfp_validate_wind(self, value):13585self.progress("validating wind(0x%02x)" % value)13586speed_m = self.bit_extract(value, 8, 7) * (10 ^ self.bit_extract(value, 7, 1)) * 0.1 # speed in m/s13587wind = self.assert_receive_message('WIND')13588self.progress("WIND mav==%f frsky==%f" % (speed_m, wind.speed))13589if abs(speed_m - wind.speed) < 0.5:13590return True13591return False1359213593def test_frsky_passthrough_do_wants(self, frsky, wants):1359413595tstart = self.get_sim_time_cached()13596while len(wants):13597self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))13598wants_copy = copy.copy(wants)13599self.drain_mav()13600t2 = self.get_sim_time_cached()13601if t2 - tstart > 300:13602self.progress("Failed to get frsky passthrough data")13603self.progress("Counts of sensor_id polls sent:")13604frsky.dump_sensor_id_poll_counts_as_progress_messages()13605self.progress("Counts of dataids received:")13606frsky.dump_dataid_counts_as_progress_messages()13607raise AutoTestTimeoutException("Failed to get frsky passthrough data")13608frsky.update()13609for want in wants_copy:13610data = frsky.get_data(want)13611if data is None:13612continue13613self.progress("Checking 0x%x" % (want,))13614if wants[want](data):13615self.progress(" Fulfilled")13616del wants[want]1361713618def FRSkyPassThroughStatustext(self):13619'''test FRSKy protocol's telem-passthrough functionality'''13620# we disable terrain here as RCTelemetry can queue a lot of13621# statustexts if terrain tiles aren't available which can13622# happen on the autotest server.13623self.set_parameters({13624"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough13625"RPM1_TYPE": 10, # enable RPM output13626"TERRAIN_ENABLE": 0,13627})13628port = self.spare_network_port()13629self.customise_SITL_commandline([13630"--serial5=tcp:%u" % port # serial5 spews to localhost port13631])13632frsky = FRSkyPassThrough(("127.0.0.1", port),13633get_time=self.get_sim_time_cached)1363413635# waiting until we are ready to arm should ensure our wanted13636# statustext doesn't get blatted out of the ArduPilot queue by13637# random messages.13638self.wait_ready_to_arm()1363913640# test we get statustext strings. This relies on ArduPilot13641# emitting statustext strings when we fetch parameters. (or,13642# now, an updating-barometer statustext)13643tstart = self.get_sim_time()13644old_data = None13645text = ""1364613647self.context_collect('STATUSTEXT')13648command = mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION13649self.send_cmd(13650command,13651p3=1, # p3, baro13652)13653# this is a test for asynchronous handling of mavlink messages:13654self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_IN_PROGRESS, 2)13655self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_ACCEPTED, 5)1365613657received_frsky_texts = []13658last_len_received_statustexts = 013659timeout = 7 * self.speedup # it can take a *long* time to get these messages down!13660while True:13661self.drain_mav()13662now = self.get_sim_time_cached()13663if now - tstart > timeout:13664raise NotAchievedException("Did not get statustext in time")13665frsky.update()13666data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats.13667if data is None:13668continue13669# frsky sends each quartet three times; skip the suplicates.13670if old_data is not None and old_data == data:13671continue13672old_data = data13673self.progress("Got (0x%x)" % data)13674severity = 013675last = False13676for i in 3, 2, 1, 0:13677x = (data >> i*8) & 0xff13678text += chr(x & 0x7f)13679self.progress(" x=0x%02x" % x)13680if x & 0x80:13681severity += 1 << i13682self.progress("Text sev=%u: %s" % (severity, str(text)))13683if (x & 0x7f) == 0x00:13684last = True13685if last:13686m = None13687text = text.rstrip("\0")13688self.progress("Received frsky text (%s)" % (text,))13689self.progress("context texts: %s" %13690str([st.text for st in self.context_collection('STATUSTEXT')]))13691m = self.statustext_in_collections(text)13692if m is not None:13693want_sev = m.severity13694if severity != want_sev:13695raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))13696self.progress("Got statustext (%s)" % m.text)13697break13698received_frsky_texts.append((severity, text))13699text = ""13700received_statustexts = self.context_collection('STATUSTEXT')13701if len(received_statustexts) != last_len_received_statustexts:13702last_len_received_statustexts = len(received_statustexts)13703self.progress("received statustexts: %s" % str([st.text for st in received_statustexts]))13704self.progress("received frsky texts: %s" % str(received_frsky_texts))13705for (want_sev, received_text) in received_frsky_texts:13706for m in received_statustexts:13707if m.text == received_text:13708if want_sev != m.severity:13709raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))13710self.progress("Got statustext (%s)" % received_text)13711break1371213713def FRSkyPassThroughSensorIDs(self):13714'''test FRSKy protocol's telem-passthrough functionality (sensor IDs)'''13715self.set_parameters({13716"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough13717"RPM1_TYPE": 10, # enable RPM output13718})13719port = self.spare_network_port()13720self.customise_SITL_commandline([13721"--serial5=tcp:%u" % port # serial5 spews to localhost port13722])13723frsky = FRSkyPassThrough(("127.0.0.1", port),13724get_time=self.get_sim_time_cached)1372513726self.wait_ready_to_arm()1372713728# we need to start the engine to get some RPM readings, we do it for plane only13729# anything with a lambda in here needs a proper test written.13730# This, at least makes sure we're getting some of each13731# message. These are ordered according to the wfq scheduler13732wants = {137330x5000: lambda xx: True,137340x5006: self.tfp_validate_attitude,137350x0800: self.tf_validate_gps,137360x5005: self.tfp_validate_vel_and_yaw,137370x5001: self.tfp_validate_ap_status,137380x5002: self.tfp_validate_gps_status,137390x5004: self.tfp_validate_home_status,13740# 0x5008: lambda x : True, # no second battery, so this doesn't arrive137410x5003: self.tfp_validate_battery1,137420x5007: self.tfp_validate_params,137430x500B: self.tfp_validate_terrain,137440x500C: self.tfp_validate_wind,13745}13746self.test_frsky_passthrough_do_wants(frsky, wants)1374713748# now check RPM:13749if self.is_plane():13750self.set_autodisarm_delay(0)13751if not self.arm_vehicle():13752raise NotAchievedException("Failed to ARM")13753self.set_rc(3, 1050)13754wants = {137550x500A: self.tfp_validate_rpm,13756}13757self.test_frsky_passthrough_do_wants(frsky, wants)13758self.zero_throttle()13759self.progress("Wait for vehicle to slow down")13760self.wait_groundspeed(0, 0.3)13761self.disarm_vehicle()1376213763self.progress("Counts of sensor_id polls sent:")13764frsky.dump_sensor_id_poll_counts_as_progress_messages()13765self.progress("Counts of dataids received:")13766frsky.dump_dataid_counts_as_progress_messages()1376713768def decode_mavlite_param_value(self, message):13769'''returns a tuple of parameter name, value'''13770(value,) = struct.unpack("<f", message[0:4])13771name = message[4:]13772return (name, value)1377313774def decode_mavlite_command_ack(self, message):13775'''returns a tuple of parameter name, value'''13776(command, result) = struct.unpack("<HB", message)13777return (command, result)1377813779def read_message_via_mavlite(self, frsky, sport_to_mavlite):13780'''read bytes from frsky mavlite stream, trying to form up a mavlite13781message'''13782tstart = self.get_sim_time()13783timeout = 30 * self.speedup/10.013784if self.valgrind or self.callgrind:13785timeout *= 1013786while True:13787self.drain_mav(quiet=True)13788tnow = self.get_sim_time_cached()13789if tnow - tstart > timeout:13790raise NotAchievedException("Did not get parameter via mavlite")13791frsky.update()13792if sport_to_mavlite.state == sport_to_mavlite.state_MESSAGE_RECEIVED:13793message = sport_to_mavlite.get_message()13794sport_to_mavlite.reset()13795# self.progress("############ message received (type=%u)" % message.msgid)13796return message1379713798def read_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):13799tstart = self.get_sim_time()13800while True:13801tnow = self.get_sim_time_cached()13802if tnow - tstart > 30 * self.speedup / 10.0:13803raise NotAchievedException("Did not get parameter via mavlite")13804message = self.read_message_via_mavlite(frsky, sport_to_mavlite)13805if message.msgid != mavutil.mavlink.MAVLINK_MSG_ID_PARAM_VALUE:13806raise NotAchievedException("Unexpected msgid %u received" % message.msgid)13807(got_name, value) = self.decode_mavlite_param_value(message.body)13808# self.progress("Received parameter: %s=%f" % (name, value))13809got_name = got_name.decode('ascii')13810if got_name != name:13811raise NotAchievedException("Incorrect name received (want=%s) (got=%s)" % (name, got_name))13812return value1381313814def get_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):13815# self.progress("########## Sending request")13816frsky.send_mavlite_param_request_read(name)13817return self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)1381813819def set_parameter_via_mavlite(self, frsky, sport_to_mavlite, name, value):13820# self.progress("########## Sending request")13821frsky.send_mavlite_param_set(name, value)13822# new value is echoed back immediately:13823got_val = self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)13824if abs(got_val - value) > 0.00001:13825raise NotAchievedException("Returned value not same as set value (want=%f got=%f)" % (value, got_val))1382613827def run_cmd_via_mavlite(self,13828frsky,13829sport_to_mavlite,13830command,13831p1=None,13832p2=None,13833p3=None,13834p4=None,13835p5=None,13836p6=None,13837p7=None,13838want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):13839frsky.send_mavlite_command_long(13840command,13841p1=p1,13842p2=p2,13843p3=p3,13844p4=p4,13845p5=p5,13846p6=p6,13847p7=p7,13848)13849self.run_cmd_via_mavlite_get_ack(13850frsky,13851sport_to_mavlite,13852command,13853want_result13854)1385513856def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_result):13857'''expect and read a command-ack from frsky sport passthrough'''13858msg = self.read_message_via_mavlite(frsky, sport_to_mavlite)13859if msg.msgid != mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_ACK:13860raise NotAchievedException("Expected a command-ack, got a %u" % msg.msgid)13861(got_command, got_result) = self.decode_mavlite_command_ack(msg.body)13862if got_command != command:13863raise NotAchievedException(13864"Did not receive expected command in command_ack; want=%u got=%u" %13865(command, got_command))13866if got_result != want_result:13867raise NotAchievedException(13868"Did not receive expected result in command_ack; want=%u got=%u" %13869(want_result, got_result))1387013871def FRSkyMAVlite(self):13872'''Test FrSky MAVlite serial output'''13873self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough13874port = self.spare_network_port()13875self.customise_SITL_commandline([13876"--serial5=tcp:%u" % port # serial5 spews to localhost port13877])13878frsky = FRSkyPassThrough(("127.0.0.1", port))13879frsky.connect()1388013881sport_to_mavlite = SPortToMAVlite()13882frsky.data_downlink_handler = sport_to_mavlite.downlink_handler1388313884self.start_subtest("Get parameter via MAVlite")13885param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles13886set_value = 97.2113887self.set_parameter(param_name, set_value) # DO NOT FLY13888got_value = self.get_parameter_via_mavlite(frsky,13889sport_to_mavlite,13890param_name)13891if abs(got_value - set_value) > 0.00001:13892raise NotAchievedException("Incorrect value retrieved via mavlite (want=%f got=%f)" % (set_value, got_value))13893self.progress("Got value OK")13894self.end_subtest("Get parameter via MAVlite")1389513896self.start_subtest("Set parameter via MAVlite")13897param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles13898set_value = 91.6713899# frsky.verbose = True13900self.set_parameter_via_mavlite(frsky, sport_to_mavlite, param_name, set_value) # DO NOT FLY13901got_value = self.get_parameter(param_name)13902if abs(got_value - set_value) > 0.00001:13903raise NotAchievedException("Incorrect value retrieved via mavlink (want=%f got=%f)" % (set_value, got_value))13904self.progress("Set value OK")13905self.end_subtest("Set parameter via MAVlite")1390613907self.start_subtest("Calibrate Baro via MAVLite")13908self.context_push()13909self.context_collect("STATUSTEXT")13910self.run_cmd_via_mavlite(13911frsky,13912sport_to_mavlite,13913mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,13914p1=0,13915p2=0,13916p3=1.0,13917)13918self.wait_statustext("Updating barometer calibration", check_context=True)13919self.context_pop()13920self.end_subtest("Calibrate Baro via MAVLite")1392113922self.start_subtest("Change mode via MAVLite")13923# FIXME: currently plane-specific13924self.run_cmd_via_mavlite(13925frsky,13926sport_to_mavlite,13927mavutil.mavlink.MAV_CMD_DO_SET_MODE,13928p1=mavutil.mavlink.PLANE_MODE_MANUAL,13929)13930self.wait_mode("MANUAL")13931self.run_cmd_via_mavlite(13932frsky,13933sport_to_mavlite,13934mavutil.mavlink.MAV_CMD_DO_SET_MODE,13935p1=mavutil.mavlink.PLANE_MODE_FLY_BY_WIRE_A,13936)13937self.wait_mode("FBWA")13938self.end_subtest("Change mode via MAVLite")1393913940self.start_subtest("Enable fence via MAVlite")13941# Fence can be enabled using MAV_CMD13942self.run_cmd_via_mavlite(13943frsky,13944sport_to_mavlite,13945mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,13946p1=1,13947want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,13948)13949self.end_subtest("Enable fence via MAVlite")1395013951def tfs_validate_gps_alt(self, value):13952self.progress("validating gps altitude (0x%02x)" % value)13953alt_m = value * 0.01 # cm -> m13954gpi = self.assert_receive_message('GLOBAL_POSITION_INT')13955if gpi is None:13956raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")13957gpi_alt_m = round(gpi.alt * 0.001) # mm-> m13958self.progress("GLOBAL_POSITION_INT alt==%f frsky==%f" % (gpi_alt_m, alt_m))13959if self.compare_number_percent(gpi_alt_m, alt_m, 10):13960return True13961return False1396213963def tfs_validate_baro_alt(self, value):13964self.progress("validating baro altitude (0x%02x)" % value)13965alt_m = value * 0.01 # cm -> m13966gpi = self.assert_receive_message('GLOBAL_POSITION_INT')13967if gpi is None:13968raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")13969gpi_alt_m = round(gpi.relative_alt * 0.001) # mm -> m13970self.progress("GLOBAL_POSITION_INT relative_alt==%f frsky==%f" % (gpi_alt_m, alt_m))13971if abs(gpi_alt_m - alt_m) < 1:13972return True13973return False1397413975def tfs_validate_gps_speed(self, value):13976self.progress("validating gps speed (0x%02x)" % value)13977speed_ms = value * 0.001 # mm/s -> m/s13978vfr_hud = self.assert_receive_message('VFR_HUD')13979vfr_hud_speed_ms = round(vfr_hud.groundspeed)13980self.progress("VFR_HUD groundspeed==%f frsky==%f" % (vfr_hud_speed_ms, speed_ms))13981if self.compare_number_percent(vfr_hud_speed_ms, speed_ms, 10):13982return True13983return False1398413985def tfs_validate_yaw(self, value):13986self.progress("validating yaw (0x%02x)" % value)13987yaw_deg = value * 0.01 # cd -> deg13988vfr_hud = self.assert_receive_message('VFR_HUD')13989vfr_hud_yaw_deg = round(vfr_hud.heading)13990self.progress("VFR_HUD heading==%f frsky==%f" % (vfr_hud_yaw_deg, yaw_deg))13991if self.compare_number_percent(vfr_hud_yaw_deg, yaw_deg, 10):13992return True13993return False1399413995def tfs_validate_vspeed(self, value):13996self.progress("validating vspeed (0x%02x)" % value)13997vspeed_ms = value * 0.01 # cm/s -> m/s13998vfr_hud = self.assert_receive_message('VFR_HUD')13999vfr_hud_vspeed_ms = round(vfr_hud.climb)14000self.progress("VFR_HUD climb==%f frsky==%f" % (vfr_hud_vspeed_ms, vspeed_ms))14001if self.compare_number_percent(vfr_hud_vspeed_ms, vspeed_ms, 10):14002return True14003return False1400414005def tfs_validate_battery1(self, value):14006self.progress("validating battery1 (0x%02x)" % value)14007voltage_v = value * 0.01 # cV -> V14008batt = self.assert_receive_message(14009'BATTERY_STATUS',14010timeout=5,14011condition="BATTERY_STATUS.id==0"14012)14013battery_status_voltage_v = batt.voltages[0] * 0.001 # mV -> V14014self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_voltage_v, voltage_v))14015if self.compare_number_percent(battery_status_voltage_v, voltage_v, 10):14016return True14017return False1401814019def tfs_validate_current1(self, value):14020# test frsky current vs BATTERY_STATUS14021self.progress("validating battery1 (0x%02x)" % value)14022current_a = value * 0.1 # dA -> A14023batt = self.assert_receive_message(14024'BATTERY_STATUS',14025timeout=5,14026condition="BATTERY_STATUS.id==0"14027)14028battery_status_current_a = batt.current_battery * 0.01 # cA -> A14029self.progress("BATTERY_STATUS current==%f frsky==%f" % (battery_status_current_a, current_a))14030if self.compare_number_percent(round(battery_status_current_a * 10), round(current_a * 10), 10):14031return True14032return False1403314034def tfs_validate_fuel(self, value):14035self.progress("validating fuel (0x%02x)" % value)14036fuel = value14037batt = self.assert_receive_message(14038'BATTERY_STATUS',14039timeout=5,14040condition="BATTERY_STATUS.id==0"14041)14042battery_status_fuel = batt.battery_remaining14043self.progress("BATTERY_STATUS fuel==%f frsky==%f" % (battery_status_fuel, fuel))14044if self.compare_number_percent(battery_status_fuel, fuel, 10):14045return True14046return False1404714048def tfs_validate_tmp1(self, value):14049self.progress("validating tmp1 (0x%02x)" % value)14050tmp1 = value14051heartbeat = self.wait_heartbeat()14052heartbeat_tmp1 = heartbeat.custom_mode14053self.progress("GLOBAL_POSITION_INT custom_mode==%f frsky==%f" % (heartbeat_tmp1, tmp1))14054if heartbeat_tmp1 == tmp1:14055return True14056return False1405714058def tfs_validate_tmp2(self, value):14059self.progress("validating tmp2 (0x%02x)" % value)14060tmp2 = value14061gps_raw = self.assert_receive_message('GPS_RAW_INT')14062gps_raw_tmp2 = gps_raw.satellites_visible*10 + gps_raw.fix_type14063self.progress("GPS_RAW_INT tmp2==%f frsky==%f" % (gps_raw_tmp2, tmp2))14064if gps_raw_tmp2 == tmp2:14065return True14066return False1406714068def tfs_validate_rpm(self, value):14069self.progress("validating rpm (0x%02x)" % value)14070tfs_rpm = value14071rpm = self.assert_receive_message('RPM', timeout=5)14072rpm_value = round(rpm.rpm1)14073self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tfs_rpm))14074if rpm_value == tfs_rpm:14075return True14076return False1407714078def wait_rpm1(self, min_rpm=None, timeout=10):14079'''wait for mavlink RPM message to indicate valid RPM'''14080tstart = self.get_sim_time()14081while True:14082t = self.get_sim_time_cached()14083if t - tstart > timeout:14084raise AutoTestTimeoutException("Failed to do get valid RPM")14085rpm = self.mav.recv_match(14086type='RPM',14087blocking=True,14088timeout=114089)14090self.progress("rpm: (%s)" % str(rpm))14091if rpm is None:14092continue14093if min_rpm is None:14094return14095if rpm.rpm1 >= min_rpm:14096return1409714098def FRSkySPort(self):14099'''Test FrSky SPort mode'''14100self.set_parameters({14101"SERIAL5_PROTOCOL": 4, # serial5 is FRSky sport14102"RPM1_TYPE": 10, # enable SITL RPM sensor14103"GPS1_TYPE": 100, # use simulated backend for consistent position14104})14105port = self.spare_network_port()14106self.customise_SITL_commandline([14107"--serial5=tcp:%u" % port # serial5 spews to localhost port14108])14109frsky = FRSkySPort(("127.0.0.1", port), verbose=True)14110self.wait_ready_to_arm()1411114112# we need to start the engine to get some RPM readings, we do it for plane only14113if self.is_plane():14114self.set_autodisarm_delay(0)14115if not self.arm_vehicle():14116raise NotAchievedException("Failed to ARM")14117self.set_rc(3, 1050)14118self.wait_rpm1(timeout=10, min_rpm=200)1411914120self.assert_current_onboard_log_contains_message("RPM")1412114122self.drain_mav()14123# anything with a lambda in here needs a proper test written.14124# This, at least makes sure we're getting some of each14125# message.14126wants = {141270x082F: self.tfs_validate_gps_alt, # gps altitude integer cm141280x040F: self.tfs_validate_tmp1, # Tmp1141290x060F: self.tfs_validate_fuel, # fuel % 0-100141300x041F: self.tfs_validate_tmp2, # Tmp2141310x010F: self.tfs_validate_baro_alt, # baro alt cm141320x083F: self.tfs_validate_gps_speed, # gps speed integer mm/s141330x084F: self.tfs_validate_yaw, # yaw in cd141340x020F: self.tfs_validate_current1, # current dA141350x011F: self.tfs_validate_vspeed, # vertical speed cm/s141360x021F: self.tfs_validate_battery1, # battery 1 voltage cV141370x0800: self.tf_validate_gps, # gps lat/lon141380x050E: self.tfs_validate_rpm, # rpm 114139}14140tstart = self.get_sim_time_cached()14141last_wanting_print = 01414214143last_data_time = None14144while len(wants):14145now = self.get_sim_time()14146if now - last_wanting_print > 1:14147self.progress("Still wanting (%s)" %14148",".join([("0x%02x" % x) for x in wants.keys()]))14149last_wanting_print = now14150wants_copy = copy.copy(wants)14151if now - tstart > 300:14152self.progress("Failed to get frsky passthrough data")14153self.progress("Counts of sensor_id polls sent:")14154frsky.dump_sensor_id_poll_counts_as_progress_messages()14155self.progress("Counts of dataids received:")14156frsky.dump_dataid_counts_as_progress_messages()14157raise AutoTestTimeoutException("Failed to get frsky sport data")14158frsky.update()14159if frsky.last_data_time == last_data_time:14160continue14161last_data_time = frsky.last_data_time14162for want in wants_copy:14163data = frsky.get_data(want)14164if data is None:14165continue14166self.progress("Checking 0x%x" % (want,))14167if wants[want](data):14168self.progress(" Fulfilled")14169del wants[want]14170# ok done, stop the engine14171if self.is_plane():14172self.zero_throttle()14173self.disarm_vehicle(force=True)1417414175def FRSkyD(self):14176'''Test FrSkyD serial output'''14177self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output14178port = self.spare_network_port()14179self.customise_SITL_commandline([14180"--serial5=tcp:%u" % port # serial5 spews to localhost port14181])14182frsky = FRSkyD(("127.0.0.1", port))14183self.wait_ready_to_arm()14184m = self.assert_receive_message('GLOBAL_POSITION_INT')14185gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m1418614187# grab a battery-remaining percentage14188self.run_cmd(14189mavutil.mavlink.MAV_CMD_BATTERY_RESET,14190p1=65535, # battery mask14191p2=96, # percentage14192)14193m = self.assert_receive_message('BATTERY_STATUS')14194want_battery_remaining_pct = m.battery_remaining1419514196tstart = self.get_sim_time_cached()14197have_alt = False14198have_battery = False14199while True:14200t2 = self.get_sim_time_cached()14201if t2 - tstart > 10:14202raise AutoTestTimeoutException("Failed to get frsky D data")14203frsky.update()1420414205alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)14206self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))14207if alt is None:14208continue14209if alt == gpi_abs_alt:14210have_alt = True1421114212batt = frsky.get_data(frsky.dataid_FUEL)14213self.progress("Got batt (%s) mav=%s" % (str(batt), str(want_battery_remaining_pct)))14214if batt is None:14215continue14216if batt == want_battery_remaining_pct:14217have_battery = True1421814219if have_alt and have_battery:14220break14221self.drain_mav()1422214223def test_ltm_g(self, ltm):14224g = ltm.g()14225if g is None:14226return14227m = self.assert_receive_message('GLOBAL_POSITION_INT')14228print("m: %s" % str(m))1422914230print("g.lat=%s m.lat=%s" % (str(g.lat()), str(m.lat)))14231if abs(m.lat - g.lat()) > 10:14232return False1423314234print("g.lon:%s m.lon:%s" % (str(g.lon()), str(m.lon)))14235if abs(m.lon - g.lon()) > 10:14236return False1423714238print("gndspeed: %s" % str(g.gndspeed()))14239if g.gndspeed() != 0:14240# FIXME if we start the vehicle moving.... check against VFR_HUD?14241return False1424214243print("g.alt=%s m.alt=%s" % (str(g.alt()/100.0), str(m.relative_alt/1000.0)))14244if abs(m.relative_alt/1000.0 - g.alt()/100.0) > 1:14245return False1424614247print("sats: %s" % str(g.sats()))14248m = self.assert_receive_message('GPS_RAW_INT')14249if m.satellites_visible != g.sats():14250return False1425114252constrained_fix_type = m.fix_type14253if constrained_fix_type > 3:14254constrained_fix_type = 314255print("fix_type: %s" % g.fix_type())14256if constrained_fix_type != g.fix_type():14257return False1425814259return True1426014261def test_ltm_a(self, ltm):14262a = ltm.a()14263if a is None:14264return14265m = self.assert_receive_message('ATTITUDE')1426614267pitch = a.pitch()14268print("pitch: %s" % str(pitch))14269if abs(math.degrees(m.pitch) - pitch) > 1:14270return False1427114272roll = a.roll()14273print("roll: %s" % str(roll))14274if abs(math.degrees(m.roll) - roll) > 1:14275return False1427614277hdg = a.hdg()14278myaw = math.degrees(m.yaw)14279myaw += 36014280myaw %= 36014281print("a.hdg=%s m.hdg=%s" % (str(hdg), str(myaw)))14282if abs(myaw - hdg) > 1:14283return False1428414285return True1428614287def test_ltm_s(self, ltm):14288s = ltm.s()14289if s is None:14290return14291# FIXME. Actually check the field values are correct :-)14292return True1429314294def LTM(self):14295'''Test LTM serial output'''14296self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output14297port = self.spare_network_port()14298self.customise_SITL_commandline([14299"--serial5=tcp:%u" % port # serial5 spews to localhost port14300])14301ltm = LTM(("127.0.0.1", port))14302self.wait_ready_to_arm()1430314304wants = {14305"g": self.test_ltm_g,14306"a": self.test_ltm_a,14307"s": self.test_ltm_s,14308}1430914310tstart = self.get_sim_time()14311while True:14312self.progress("Still wanting (%s)" %14313",".join([("%s" % x) for x in wants.keys()]))14314if len(wants) == 0:14315break14316now = self.get_sim_time_cached()14317if now - tstart > 10:14318raise AutoTestTimeoutException("Failed to get ltm data")1431914320ltm.update()1432114322wants_copy = copy.copy(wants)14323for want in wants_copy:14324self.progress("Checking %s" % (want,))14325if wants[want](ltm):14326self.progress(" Fulfilled")14327del wants[want]1432814329def convertDmsToDdFormat(self, dms):14330deg = math.trunc(dms * 1e-7)14331dd = deg + (((dms * 1.0e-7) - deg) * 100.0 / 60.0)14332if dd < -180.0 or dd > 180.0:14333dd = 0.014334return math.trunc(dd * 1.0e7)1433514336def DEVO(self):14337'''Test DEVO serial output'''14338self.context_push()14339self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output14340port = self.spare_network_port()14341self.customise_SITL_commandline([14342"--serial5=tcp:%u" % port # serial5 spews to localhost port14343])14344devo = DEVO(("127.0.0.1", port))14345self.wait_ready_to_arm()14346m = self.assert_receive_message('GLOBAL_POSITION_INT')1434714348tstart = self.get_sim_time_cached()14349while True:14350self.drain_mav()14351now = self.get_sim_time_cached()14352if now - tstart > 10:14353if devo.frame is not None:14354# we received some frames but could not find correct values14355raise AutoTestTimeoutException("Failed to get correct data")14356else:14357# No frames received. Devo telemetry is compiled out?14358break1435914360devo.update()14361frame = devo.frame14362if frame is None:14363continue1436414365m = self.assert_receive_message('GLOBAL_POSITION_INT')1436614367loc = LocationInt(self.convertDmsToDdFormat(frame.lat()), self.convertDmsToDdFormat(frame.lon()), 0, 0)1436814369print("received lat:%s expected lat:%s" % (str(loc.lat), str(m.lat)))14370print("received lon:%s expected lon:%s" % (str(loc.lon), str(m.lon)))14371dist_diff = self.get_distance_int(loc, m)14372print("Distance:%s" % str(dist_diff))14373if abs(dist_diff) > 2:14374continue1437514376gpi_rel_alt = int(m.relative_alt / 10) # mm -> cm, since driver send alt in cm14377print("received alt:%s expected alt:%s" % (str(frame.alt()), str(gpi_rel_alt)))14378if abs(gpi_rel_alt - frame.alt()) > 10:14379continue1438014381print("received gndspeed: %s" % str(frame.speed()))14382if frame.speed() != 0:14383# FIXME if we start the vehicle moving.... check against VFR_HUD?14384continue1438514386print("received temp:%s expected temp:%s" % (str(frame.temp()), str(self.mav.messages['HEARTBEAT'].custom_mode)))14387if frame.temp() != self.mav.messages['HEARTBEAT'].custom_mode:14388# currently we receive mode as temp. This should be fixed when driver is updated14389continue1439014391# we match the received voltage with the voltage of primary instance14392batt = self.assert_receive_message(14393'BATTERY_STATUS',14394timeout=5,14395condition="BATTERY_STATUS.id==0"14396)14397volt = batt.voltages[0]*0.00114398print("received voltage:%s expected voltage:%s" % (str(frame.volt()*0.1), str(volt)))14399if abs(frame.volt()*0.1 - volt) > 0.1:14400continue14401# if we reach here, exit14402break14403self.context_pop()14404self.reboot_sitl()1440514406def MSP_DJI(self):14407'''Test MSP DJI serial output'''14408self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output14409self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode14410port = self.spare_network_port()14411self.customise_SITL_commandline([14412"--serial5=tcp:%u" % port # serial5 spews to localhost port14413])14414msp = MSP_DJI(("127.0.0.1", port))14415self.wait_ready_to_arm()1441614417tstart = self.get_sim_time()14418while True:14419self.drain_mav()14420if self.get_sim_time_cached() - tstart > 10:14421raise NotAchievedException("Did not get location")14422msp.update()14423try:14424f = msp.get_frame(msp.FRAME_GPS_RAW)14425except KeyError:14426continue14427dist = self.get_distance_int(f.LocationInt(), self.sim_location_int())14428print("lat=%f lon=%f dist=%f" % (f.lat(), f.lon(), dist))14429if dist < 1:14430break1443114432def CRSF(self):14433'''Test RC CRSF'''14434self.context_push()14435ex = None14436try:14437self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input14438port = self.spare_network_port()14439self.customise_SITL_commandline([14440"--serial5=tcp:%u" % port # serial5 reads from to localhost port14441])14442crsf = CRSF(("127.0.0.1", port))14443crsf.connect()1444414445self.progress("Writing vtx_frame")14446crsf.write_data_id(crsf.dataid_vtx_frame)14447self.delay_sim_time(5)14448self.progress("Writing vtx_telem")14449crsf.write_data_id(crsf.dataid_vtx_telem)14450self.delay_sim_time(5)14451self.progress("Writing vtx_unknown")14452crsf.write_data_id(crsf.dataid_vtx_unknown)14453self.delay_sim_time(5)14454except Exception as e:14455self.print_exception_caught(e)14456ex = e14457self.context_pop()14458self.disarm_vehicle(force=True)14459self.reboot_sitl()14460if ex is not None:14461raise ex1446214463def CompassPrearms(self):14464'''test compass prearm checks'''14465self.wait_ready_to_arm()14466# XY are checked specially:14467for axis in 'X', 'Y': # ArduPilot only checks these two axes14468self.context_push()14469self.set_parameter(f"COMPASS_OFS2_{axis}", 1000)14470self.assert_prearm_failure("Compasses inconsistent")14471self.context_pop()14472self.wait_ready_to_arm()1447314474# now test the total anglular difference:14475self.context_push()14476self.set_parameters({14477"COMPASS_OFS2_X": 1000,14478"COMPASS_OFS2_Y": -1000,14479"COMPASS_OFS2_Z": -10000,14480})14481self.assert_prearm_failure("Compasses inconsistent")14482self.context_pop()14483self.wait_ready_to_arm()14484# the following line papers over a probably problem with the14485# EKF recovering from bad compass offsets. Without it, the14486# EKF will maintain a 10-degree offset from the true compass14487# heading seemingly indefinitely.14488self.reboot_sitl()1448914490def run_replay(self, filepath):14491'''runs replay in filepath, returns filepath to Replay logfile'''14492util.run_cmd(14493['build/sitl/tool/Replay', filepath],14494directory=util.topdir(),14495checkfail=True,14496show=True,14497output=True,14498)14499return self.current_onboard_log_filepath()1450014501def AHRS_ORIENTATION(self):14502'''test AHRS_ORIENTATION parameter works'''14503self.context_push()14504self.wait_ready_to_arm()14505original_imu = self.assert_receive_message("RAW_IMU", verbose=True)14506self.set_parameter("AHRS_ORIENTATION", 16) # roll-9014507self.delay_sim_time(2) # we update this on a timer14508new_imu = self.assert_receive_message("RAW_IMU", verbose=True)14509delta_zacc = original_imu.zacc - new_imu.zacc14510delta_z_g = delta_zacc/1000.0 # milligravities -> gravities14511if delta_z_g - 1 > 0.1: # milligravities....14512raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_z_g=%f)" % (delta_z_g,))14513delta_yacc = original_imu.yacc - new_imu.yacc14514delta_y_g = delta_yacc/1000.0 # milligravities -> gravities14515if delta_y_g + 1 > 0.1:14516raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_y_g=%f)" % (delta_y_g,))14517self.context_pop()14518self.reboot_sitl()14519self.delay_sim_time(2) # we update orientation on a timer1452014521def GPSTypes(self):14522'''check each simulated GPS works'''14523self.reboot_sitl()14524orig = self.poll_home_position(timeout=60)14525sim_gps = [14526# (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix)14527# if gps_type is None we auto-detect14528# (0, "NONE"),14529(1, "UBLOX", None, "u-blox", 5, 'probing'),14530(5, "NMEA", 5, "NMEA", 5, 'probing'),14531(6, "SBP", None, "SBP", 5, 'probing'),14532(8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS14533(9, "SBP2", None, "SBP2", 5, 'probing'),14534(10, "SBF", 10, 'SBF', 5, 'probing'),14535(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS14536(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS14537# (9, "FILE"),14538]14539self.context_collect("STATUSTEXT")14540for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:14541self.start_subtest("Checking GPS type %s" % name)14542self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)14543self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)14544if gps_type is None:14545gps_type = 1 # auto-detect14546self.set_parameter("GPS1_TYPE", gps_type)14547self.context_clear_collection('STATUSTEXT')14548self.reboot_sitl()14549if detect_prefix == "probing":14550self.wait_statustext(f"probing for {detect_name}", check_context=True)14551else:14552self.wait_statustext(f"specified as {detect_name}", check_context=True)14553self.wait_statustext(f"detected {detect_name}", check_context=True)14554n = self.poll_home_position(timeout=120)14555distance = self.get_distance_int(orig, n)14556if distance > 1:14557raise NotAchievedException(f"gps type {name} misbehaving")1455814559def assert_gps_satellite_count(self, messagename, count):14560m = self.assert_receive_message(messagename)14561if m.satellites_visible != count:14562raise NotAchievedException("Expected %u sats, got %u" %14563(count, m.satellites_visible))1456414565def check_attitudes_match(self):14566'''make sure ahrs2 and simstate and ATTTIUDE_QUATERNION all match'''1456714568# these are ordered to bookend the list with timestamps (which14569# both attitude messages have):14570get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']14571msgs = self.get_messages_frame(get_names)1457214573for get_name in get_names:14574self.progress("%s: %s" % (get_name, msgs[get_name]))1457514576simstate = msgs['SIMSTATE']14577attitude = msgs['ATTITUDE']14578ahrs2 = msgs['AHRS2']14579attitude_quaternion = msgs['ATTITUDE_QUATERNION']1458014581# check ATTITUDE14582want = math.degrees(simstate.roll)14583got = math.degrees(attitude.roll)14584if abs(mavextra.angle_diff(want, got)) > 20:14585raise NotAchievedException("ATTITUDE.Roll looks bad (want=%f got=%f)" %14586(want, got))14587want = math.degrees(simstate.pitch)14588got = math.degrees(attitude.pitch)14589if abs(mavextra.angle_diff(want, got)) > 20:14590raise NotAchievedException("ATTITUDE.Pitch looks bad (want=%f got=%f)" %14591(want, got))1459214593# check AHRS214594want = math.degrees(simstate.roll)14595got = math.degrees(ahrs2.roll)14596if abs(mavextra.angle_diff(want, got)) > 20:14597raise NotAchievedException("AHRS2.Roll looks bad (want=%f got=%f)" %14598(want, got))1459914600want = math.degrees(simstate.pitch)14601got = math.degrees(ahrs2.pitch)14602if abs(mavextra.angle_diff(want, got)) > 20:14603raise NotAchievedException("AHRS2.Pitch looks bad (want=%f got=%f)" %14604(want, got))1460514606# check ATTITUDE_QUATERNION14607q = quaternion.Quaternion([14608attitude_quaternion.q1,14609attitude_quaternion.q2,14610attitude_quaternion.q3,14611attitude_quaternion.q414612])14613euler = q.euler14614self.progress("attquat:%s q:%s euler:%s" % (14615str(attitude_quaternion), q, euler))1461614617want = math.degrees(simstate.roll)14618got = math.degrees(euler[0])14619if mavextra.angle_diff(want, got) > 20:14620raise NotAchievedException("quat roll differs from attitude roll; want=%f got=%f" %14621(want, got))1462214623want = math.degrees(simstate.pitch)14624got = math.degrees(euler[1])14625if mavextra.angle_diff(want, got) > 20:14626raise NotAchievedException("quat pitch differs from attitude pitch; want=%f got=%f" %14627(want, got))1462814629def MultipleGPS(self):14630'''check ArduPilot behaviour across multiple GPS units'''14631self.assert_message_rate_hz('GPS2_RAW', 0)1463214633# we start sending GPS2_TYPE - but it will never actually be14634# filled in as _port[1] is only filled in in AP_GPS::init()14635self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")14636self.set_parameter("GPS2_TYPE", 1)14637self.assert_message_rate_hz('GPS2_RAW', 5)1463814639self.start_subtest("Ensure correct fix type when no connected GPS")14640m = self.assert_receive_message("GPS2_RAW")14641self.progress(self.dump_message_verbose(m))14642if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_NO_GPS:14643raise NotAchievedException("Incorrect fix type")1464414645self.start_subtest("Ensure detection when sim gps connected")14646self.set_parameter("SIM_GPS2_TYPE", 1)14647self.set_parameter("SIM_GPS2_ENABLE", 1)14648# a reboot is required after setting GPS2_TYPE. We start14649# sending GPS2_RAW out, once the parameter is set, but a14650# reboot is required because _port[1] is only set in14651# AP_GPS::init() at boot time, so it will never be detected.14652self.context_collect("STATUSTEXT")14653self.reboot_sitl()14654self.wait_statustext("GPS 1: detected u-blox", check_context=True)14655self.wait_statustext("GPS 2: detected u-blox", check_context=True)14656m = self.assert_receive_message("GPS2_RAW")14657self.progress(self.dump_message_verbose(m))14658# would be nice for it to take some time to get a fix....14659if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_RTK_FIXED:14660raise NotAchievedException("Incorrect fix type")1466114662self.start_subtest("Check parameters are per-GPS")14663self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)14664self.assert_gps_satellite_count("GPS_RAW_INT", 10)14665self.set_parameter("SIM_GPS1_NUMSATS", 13)14666self.assert_gps_satellite_count("GPS_RAW_INT", 13)1466714668self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)14669self.assert_gps_satellite_count("GPS2_RAW", 10)14670self.set_parameter("SIM_GPS2_NUMSATS", 12)14671self.assert_gps_satellite_count("GPS2_RAW", 12)1467214673self.start_subtest("check that GLOBAL_POSITION_INT fails over")14674m = self.assert_receive_message("GLOBAL_POSITION_INT")14675gpi_alt = m.alt14676for msg in ["GPS_RAW_INT", "GPS2_RAW"]:14677m = self.assert_receive_message(msg)14678if abs(m.alt - gpi_alt) > 100: # these are in mm14679raise NotAchievedException("Alt (%s) discrepancy; %d vs %d" %14680(msg, m.alt, gpi_alt))14681introduced_error = 10 # in metres14682self.set_parameter("SIM_GPS2_ALT_OFS", introduced_error)14683self.do_timesync_roundtrip()14684m = self.assert_receive_message("GPS2_RAW")14685if abs((m.alt-introduced_error*1000) - gpi_alt) > 100:14686raise NotAchievedException("skewed Alt (%s) discrepancy; %d+%d vs %d" %14687(msg, introduced_error*1000, m.alt, gpi_alt))14688m = self.assert_receive_message("GLOBAL_POSITION_INT")14689new_gpi_alt = m.alt14690if abs(gpi_alt - new_gpi_alt) > 100:14691raise NotAchievedException("alt moved unexpectedly")14692self.progress("Killing first GPS")14693self.set_parameter("SIM_GPS1_ENABLE", 0)14694self.delay_sim_time(1)14695self.progress("Checking altitude now matches second GPS")14696m = self.assert_receive_message("GLOBAL_POSITION_INT")14697new_gpi_alt2 = m.alt14698m = self.assert_receive_message("GPS2_RAW")14699if abs(new_gpi_alt2 - m.alt) > 100:14700raise NotAchievedException("Failover not detected")1470114702def fetch_file_via_ftp(self, path, timeout=20):14703'''returns the content of the FTP'able file at path'''14704self.progress("Retrieving (%s) using MAVProxy" % path)14705mavproxy = self.start_mavproxy()14706mavproxy.expect("Saved .* parameters to")14707ex = None14708tmpfile = tempfile.NamedTemporaryFile(mode='r', delete=False)14709try:14710mavproxy.send("module load ftp\n")14711mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])14712mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message14713mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))14714mavproxy.expect("Getting")14715tstart = self.get_sim_time()14716while True:14717now = self.get_sim_time()14718if now - tstart > timeout:14719raise NotAchievedException("expected complete transfer")14720self.progress("Polling status")14721mavproxy.send("ftp status\n")14722try:14723mavproxy.expect("No transfer in progress", timeout=1)14724break14725except Exception:14726continue14727# terminate the connection, or it may still be in progress the next time an FTP is attempted:14728mavproxy.send("ftp cancel\n")14729mavproxy.expect("Terminated session")14730except Exception as e:14731self.print_exception_caught(e)14732ex = e1473314734self.stop_mavproxy(mavproxy)1473514736if ex is not None:14737raise ex1473814739return tmpfile.read()1474014741def MAVFTP(self):14742'''ensure MAVProxy can do MAVFTP to ardupilot'''14743mavproxy = self.start_mavproxy()14744ex = None14745try:14746mavproxy.send("module load ftp\n")14747mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])14748mavproxy.send("ftp list\n")14749some_directory = None14750for entry in sorted(os.listdir(".")):14751if os.path.isdir(entry):14752some_directory = entry14753break14754if some_directory is None:14755raise NotAchievedException("No directories?!")14756expected_line = " D %s" % some_directory14757mavproxy.expect(expected_line) # one line from the ftp list output14758except Exception as e:14759self.print_exception_caught(e)14760ex = e1476114762self.stop_mavproxy(mavproxy)1476314764if ex is not None:14765raise ex1476614767def write_content_to_filepath(self, content, filepath):14768'''write biunary content to filepath'''14769if not isinstance(content, bytes):14770raise NotAchievedException("Want bytes to write_content_to_filepath")14771with open(filepath, "wb") as f:14772f.write(content)14773f.close()1477414775def add_embedded_params_to_binary(self, binary, defaults):14776sys.path.insert(1, os.path.join(self.rootdir(), 'Tools', 'scripts'))14777import apj_tool1477814779# copy binary14780if getattr(self, "embedded_default_counter", None) is None:14781self.embedded_default_counter = 014782self.embedded_default_counter += 11478314784new_filepath = binary + "-newdefaults-%u" % self.embedded_default_counter14785shutil.copy(binary, new_filepath)1478614787# create file for defaults14788defaults_filepath = "embed-these-defaults.txt"14789self.write_content_to_filepath(defaults.encode('utf-8'), defaults_filepath)1479014791# do the needful14792a = apj_tool.embedded_defaults(new_filepath)14793if not a.find():14794raise NotAchievedException("Did not find defaults")14795a.set_file(defaults_filepath)14796a.save()1479714798return new_filepath1479914800def sample_param_file_content(self):14801'''returns an array of tuples, (param file content, dictionary of what14802parameter values should be tested afterwards)'''14803dashes = "-" * 15014804return [14805# multiple lines:14806("""SERIAL5_BAUD 123414807SERIAL4_BAUD=456714808""", {"SERIAL5_BAUD": 1234, "SERIAL4_BAUD": 4567}),1480914810# line missing CR:14811("""SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 6789}),1481214813# commented-out line:14814("""# SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 57}),1481514816# very long comment line followed by more text:14817("""SERIAL4_BAUD 678914818# awesome dashes: %s14819SERIAL5_BAUD 12814820""" % dashes, {"SERIAL4_BAUD": 6789, "SERIAL5_BAUD": 128}),1482114822]1482314824def EmbeddedParamParser(self):14825'''check parsing of embedded defaults file'''14826# warning: don't try this test on Copter as it won't boot14827# without the passed-in file (which we don't parse if there14828# are embedded defaults)14829for (content, param_values) in self.sample_param_file_content():14830binary_with_defaults = self.add_embedded_params_to_binary(self.binary, content)14831self.customise_SITL_commandline([], binary=binary_with_defaults)14832self.assert_parameter_values(param_values)1483314834def _MotorTest(self,14835command,14836timeout=60,14837mot1_servo_chan=1,14838mot4_servo_chan=4,14839wait_finish_text=True,14840quadplane=False):14841'''Run Motor Tests (with specific mavlink message)'''14842self.start_subtest("Testing PWM output")14843pwm_in = 130014844# default frame is "+" - start motor of 2 is "B", which is14845# motor 1... see14846# https://ardupilot.org/copter/docs/connect-escs-and-motors.html14847command(14848mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,14849p1=2, # start motor14850p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,14851p3=pwm_in, # pwm-to-output14852p4=2, # timeout in seconds14853p5=2, # number of motors to output14854p6=0, # compass learning14855timeout=timeout,14856)14857# long timeouts here because there's a pause before we start motors14858self.wait_servo_channel_value(mot1_servo_chan, pwm_in, timeout=10)14859self.wait_servo_channel_value(mot4_servo_chan, pwm_in, timeout=10)14860if wait_finish_text:14861self.wait_statustext("finished motor test")14862self.wait_disarmed()14863# wait_disarmed is not sufficient here; it's actually the14864# *motors* being armed which causes the problem, not the14865# vehicle's arm state! Could we use SYS_STATUS here instead?14866self.delay_sim_time(10)14867self.end_subtest("Testing PWM output")1486814869self.start_subtest("Testing percentage output")14870percentage = 90.114871# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC314872# min/max are used.14873expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.014874# quadplane doesn't use the expect value - it wants 190014875# rather than the calculated 1901...14876if quadplane:14877expected_pwm = 190014878self.progress("expected pwm=%f" % expected_pwm)14879command(14880mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,14881p1=2, # start motor14882p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,14883p3=percentage, # pwm-to-output14884p4=2, # timeout in seconds14885p5=2, # number of motors to output14886p6=0, # compass learning14887timeout=timeout,14888)14889self.wait_servo_channel_value(mot1_servo_chan, expected_pwm, timeout=10)14890self.wait_servo_channel_value(mot4_servo_chan, expected_pwm, timeout=10)14891if wait_finish_text:14892self.wait_statustext("finished motor test")14893self.wait_disarmed()14894# wait_disarmed is not sufficient here; it's actually the14895# *motors* being armed which causes the problem, not the14896# vehicle's arm state! Could we use SYS_STATUS here instead?14897self.delay_sim_time(10)14898self.end_subtest("Testing percentage output")1489914900def MotorTest(self, timeout=60, **kwargs):14901'''Run Motor Tests''' # common to Copter and QuadPlane14902self._MotorTest(self.run_cmd, **kwargs)14903self._MotorTest(self.run_cmd_int, **kwargs)1490414905def test_ibus_voltage(self, message):14906batt = self.assert_receive_message(14907'BATTERY_STATUS',14908timeout=5,14909condition="BATTERY_STATUS.id==0"14910)14911if batt is None:14912raise NotAchievedException("Did not get BATTERY_STATUS message")14913want = int(batt.voltages[0] * 0.1)1491414915if want != message.get_sensor_value():14916raise NotAchievedException("Bad voltage (want=%u got=%u)" %14917(want, message.get_sensor_value()))14918self.progress("iBus voltage OK")1491914920def test_ibus_armed(self, message):14921got = message.get_sensor_value()14922want = 1 if self.armed() else 014923if got != want:14924raise NotAchievedException("Expected armed %u got %u" %14925(want, got))14926self.progress("iBus armed OK")1492714928def test_ibus_mode(self, message):14929got = message.get_sensor_value()14930want = self.mav.messages['HEARTBEAT'].custom_mode14931if got != want:14932raise NotAchievedException("Expected mode %u got %u" %14933(want, got))14934self.progress("iBus mode OK")1493514936def test_ibus_get_response(self, ibus, timeout=5):14937tstart = self.get_sim_time()14938while True:14939now = self.get_sim_time()14940if now - tstart > timeout:14941raise AutoTestTimeoutException("Failed to get ibus data")14942packet = ibus.update()14943if packet is not None:14944return packet1494514946def IBus(self):14947'''test the IBus protocol'''14948self.set_parameter("SERIAL5_PROTOCOL", 49)14949self.customise_SITL_commandline([14950"--serial5=tcp:6735" # serial5 spews to localhost:673514951])14952ibus = IBus(("127.0.0.1", 6735))14953ibus.connect()1495414955# expected_sensors should match the list created in AP_IBus_Telem14956expected_sensors = {14957# sensor id : (len, IBUS_MEAS_TYPE_*, test_function)149581: (2, 0x15, self.test_ibus_armed),149592: (2, 0x16, self.test_ibus_mode),149605: (2, 0x03, self.test_ibus_voltage),14961}1496214963for (sensor_addr, results) in expected_sensors.items():14964# first make sure it is present:14965request = IBusRequest_DISCOVER(sensor_addr)14966ibus.port.sendall(request.for_wire())1496714968packet = self.test_ibus_get_response(ibus)14969if packet.address != sensor_addr:14970raise ValueError("Unexpected sensor address %u" %14971(packet.address,))1497214973(expected_length, expected_type, validator) = results1497414975self.progress("Getting sensor (%x) type" % (sensor_addr))14976request = IBusRequest_GET_SENSOR_TYPE(sensor_addr)14977ibus.port.sendall(request.for_wire())1497814979packet = self.test_ibus_get_response(ibus)14980if packet.address != sensor_addr:14981raise ValueError("Unexpected sensor address %u" %14982(packet.address,))1498314984if packet.sensor_type != expected_type:14985raise ValueError("Unexpected sensor type want=%u got=%u" %14986(expected_type, packet.sensor_type))1498714988if packet.sensor_length != expected_length:14989raise ValueError("Unexpected sensor len want=%u got=%u" %14990(expected_length, packet.sensor_length))1499114992self.progress("Getting sensor (%x) value" % (sensor_addr))14993request = IBusRequest_GET_SENSOR_VALUE(sensor_addr)14994ibus.port.sendall(request.for_wire())1499514996packet = self.test_ibus_get_response(ibus)14997validator(packet)1499814999# self.progress("Ensure we cover all sensors")15000# for i in range(1, 17): # zero is special15001# if i in expected_sensors:15002# continue15003# request = IBusRequest_DISCOVER(i)15004# ibus.port.sendall(request.for_wire())1500515006# try:15007# packet = self.test_ibus_get_response(ibus, timeout=1)15008# except AutoTestTimeoutException:15009# continue15010# self.progress("Received packet (%s)" % str(packet))15011# raise NotAchievedException("IBus sensor %u is untested" % i)1501215013def tests(self):15014return [15015self.PIDTuning,15016self.ArmFeatures,15017self.SetHome,15018self.ConfigErrorLoop,15019self.CPUFailsafe,15020self.Parameters,15021self.LoggerDocumentation,15022self.Logging,15023self.GetCapabilities,15024self.InitialMode,15025]1502615027def post_tests_announcements(self):15028if self._show_test_timings:15029if self.waiting_to_arm_count == 0:15030avg = None15031else:15032avg = self.total_waiting_to_arm_time/self.waiting_to_arm_count15033self.progress("Spent %f seconds waiting to arm. count=%u avg=%s" %15034(self.total_waiting_to_arm_time,15035self.waiting_to_arm_count,15036str(avg)))15037self.show_test_timings()15038if self.forced_post_test_sitl_reboots != 0:15039print("Had to force-reset SITL %u times" %15040(self.forced_post_test_sitl_reboots,))1504115042def autotest(self, tests=None, allow_skips=True, step_name=None):15043"""Autotest used by ArduPilot autotest CI."""15044if tests is None:15045tests = self.tests()15046all_tests = []15047for test in tests:15048if not isinstance(test, Test):15049test = Test(test)15050all_tests.append(test)1505115052disabled = self.disabled_tests()15053if not allow_skips:15054disabled = {}15055skip_list = []15056tests = []15057seen_test_name = set()15058for test in all_tests:15059if test.name in seen_test_name:15060raise ValueError("Duplicate test name %s" % test.name)15061seen_test_name.add(test.name)15062if test.name in disabled:15063self.progress("##### %s is skipped: %s" % (test, disabled[test.name]))15064skip_list.append((test, disabled[test.name]))15065continue15066tests.append(test)1506715068results = self.run_tests(tests)1506915070if len(skip_list):15071self.progress("Skipped tests:")15072for skipped in skip_list:15073(test, reason) = skipped15074print(" %s (see %s)" % (test.name, reason))1507515076self.fail_list = list(filter(lambda x : not x.passed, results))15077if len(self.fail_list):15078self.progress("Failing tests:")15079for failure in self.fail_list:15080print(str(failure))1508115082self.post_tests_announcements()15083if self.generate_junit:15084if step_name is None:15085step_name = "Unknown_step_name"15086step_name.replace(".", "_")15087self.create_junit_report(step_name, results, skip_list)1508815089return len(self.fail_list) == 01509015091def wait_circling_point_with_radius(self, loc, want_radius, epsilon=5.0, min_circle_time=5, timeout=120, track_angle=True):15092on_radius_start_heading = None15093average_radius = 0.015094done_time = False15095done_angle = False15096tstart = self.get_sim_time()15097circle_time_start = tstart15098while True:15099now = self.get_sim_time()15100if now - tstart > timeout:15101raise AutoTestTimeoutException("Did not get onto circle")15102here = self.mav.location()15103got_radius = self.get_distance(loc, here)15104average_radius = 0.95*average_radius + 0.05*got_radius15105on_radius = abs(got_radius - want_radius) < epsilon15106m = self.assert_receive_message('VFR_HUD')15107heading = m.heading15108on_string = "off"15109got_angle = ""15110if on_radius_start_heading is not None:15111got_angle = "%0.2f" % abs(on_radius_start_heading - heading) # FIXME15112on_string = "on"1511315114want_angle = 180 # we don't actually get this (angle-substraction issue. But we get enough...15115got_circle_time = self.get_sim_time() - circle_time_start15116bits = [15117f"wait-circling: got-r={got_radius:.2f} want-r={want_radius}",15118f"avg-r={average_radius} {on_string}",15119f"t={got_circle_time:0.2f}/{min_circle_time}",15120]15121if track_angle:15122bits.append(f"want-a={want_angle:0.1f} got-a={got_angle}")1512315124self.progress(" ".join(bits))15125if on_radius:15126if on_radius_start_heading is None:15127on_radius_start_heading = heading15128average_radius = got_radius15129circle_time_start = now15130continue15131if abs(on_radius_start_heading - heading) > want_angle: # FIXME15132done_angle = True15133if got_circle_time > min_circle_time:15134done_time = True15135if not track_angle:15136done_angle = True15137if done_time and done_angle:15138return15139continue15140on_radius_start_heading = None15141circle_time_start = now1514215143def create_junit_report(self, test_name: str, results: List[Result], skip_list: List[Tuple[Test, Dict[str, str]]]) -> None:15144"""Generate Junit report from the autotest results"""15145from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure15146frame = self.vehicleinfo_key()15147xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml"15148self.progress(f"Writing test result in jUnit format to {xml_filename}\n")1514915150suite = TestSuite(f"Autotest {frame} {test_name}")15151suite.timestamp = datetime.now().replace(microsecond=0).isoformat()15152for result in results:15153case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed)15154# f"{result.test.description}"15155# case.file ## TODO : add file properties to match test location15156if not result.passed:15157case.result = [Failure(f"see {result.debug_filename}", f"{result.exception}")]15158suite.add_testcase(case)15159for skipped in skip_list:15160(test, reason) = skipped15161case = TestCase(f"{test.name}", f"{test.function}")15162case.result = [Skipped(f"Skipped : {reason}")]1516315164suite.add_property("Firmware Version Major", self.fcu_firmware_version[0])15165suite.add_property("Firmware Version Minor", self.fcu_firmware_version[1])15166suite.add_property("Firmware Version Rev", self.fcu_firmware_version[2])15167suite.add_property("Firmware hash", self.fcu_firmware_hash)15168suite.add_property("Git hash", self.githash)15169mavproxy_version = util.MAVProxy_version()15170suite.add_property("Mavproxy Version Major", mavproxy_version[0])15171suite.add_property("Mavproxy Version Minor", mavproxy_version[1])15172suite.add_property("Mavproxy Version Rev", mavproxy_version[2])1517315174xml = JUnitXml()15175xml.add_testsuite(suite)15176xml.write(xml_filename, pretty=True)1517715178def mavfft_fttd(self, sensor_type, sensor_instance, since, until):15179'''display fft for raw ACC data in current logfile'''1518015181'''object to store data about a single FFT plot'''15182class MessageData(object):15183def __init__(self, ffth):15184self.seqno = -115185self.fftnum = ffth.N15186self.sensor_type = ffth.type15187self.instance = ffth.instance15188self.sample_rate_hz = ffth.smp_rate15189self.multiplier = ffth.mul15190self.sample_us = ffth.SampleUS15191self.data = {}15192self.data["X"] = []15193self.data["Y"] = []15194self.data["Z"] = []15195self.holes = False15196self.freq = None1519715198def add_fftd(self, fftd):15199self.seqno += 115200self.data["X"].extend(fftd.x)15201self.data["Y"].extend(fftd.y)15202self.data["Z"].extend(fftd.z)1520315204mlog = self.dfreader_for_current_onboard_log()1520515206# see https://holometer.fnal.gov/GH_FFT.pdf for a description of the techniques used here15207messages = []15208messagedata = None15209while True:15210m = mlog.recv_match()15211if m is None:15212break15213msg_type = m.get_type()15214if msg_type == "ISBH":15215if messagedata is not None:15216if (messagedata.sensor_type == sensor_type and15217messagedata.instance == sensor_instance and15218messagedata.sample_us > since and15219messagedata.sample_us < until):15220messages.append(messagedata)15221messagedata = MessageData(m)15222continue1522315224if msg_type == "ISBD":15225if (messagedata is not None and15226messagedata.sensor_type == sensor_type and15227messagedata.instance == sensor_instance):15228messagedata.add_fftd(m)1522915230fft_len = len(messages[0].data["X"])15231sum_fft = {15232"X": numpy.zeros(int(fft_len / 2 + 1)),15233"Y": numpy.zeros(int(fft_len / 2 + 1)),15234"Z": numpy.zeros(int(fft_len / 2 + 1)),15235}15236sample_rate = 015237counts = 015238window = numpy.hanning(fft_len)15239# The returned float array f contains the frequency bin centers in cycles per unit of the15240# sample spacing (with zero at the start).15241freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz)1524215243# calculate NEBW constant15244S2 = numpy.inner(window, window)1524515246for message in messages:15247for axis in ["X", "Y", "Z"]:15248# normalize data and convert to dps in order to produce more meaningful magnitudes15249if message.sensor_type == 1:15250d = numpy.array(numpy.degrees(message.data[axis])) / float(message.multiplier)15251else:15252d = numpy.array(message.data[axis]) / float(message.multiplier)1525315254# apply window to the input15255d *= window15256# perform RFFT15257d_fft = numpy.fft.rfft(d)15258# convert to squared complex magnitude15259d_fft = numpy.square(abs(d_fft))15260# remove DC component15261d_fft[0] = 015262d_fft[-1] = 015263# accumulate the sums15264sum_fft[axis] += d_fft1526515266sample_rate = message.sample_rate_hz15267counts += 11526815269numpy.seterr(divide='ignore')15270psd = {}15271for axis in ["X", "Y", "Z"]:15272# normalize output to averaged PSD15273psd[axis] = 2 * (sum_fft[axis] / counts) / (sample_rate * S2)15274psd[axis] = 10 * numpy.log10(psd[axis])1527515276psd["F"] = freqmap1527715278return psd1527915280def model_defaults_filepath(self, model, vehicleinfo_key=None):15281if vehicleinfo_key is None:15282vehicle = self.vehicleinfo_key()15283else:15284vehicle = vehicleinfo_key1528515286vinfo = vehicleinfo.VehicleInfo()15287defaults_filepath = vinfo.options[vehicle]["frames"][model]["default_params_filename"]15288if isinstance(defaults_filepath, str):15289defaults_filepath = [defaults_filepath]15290defaults_list = []15291for d in defaults_filepath:15292defaults_list.append(util.reltopdir(os.path.join(testdir, d)))15293return defaults_list1529415295def load_default_params_file(self, filename):15296'''load a file from Tools/autotest/default_params'''15297filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename))15298self.repeatedly_apply_parameter_filepath(filepath)1529915300def load_params_file(self, filename):15301'''load a file from test-specific directory'''15302filepath = os.path.join(testdir, self.current_test_name_directory, filename)15303self.repeatedly_apply_parameter_filepath(filepath)1530415305def send_pause_command(self):15306'''pause AUTO/GUIDED modes'''15307self.run_cmd(15308mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,15309p1=0, # 0: pause, 1: continue15310)1531115312def send_resume_command(self):15313'''resume AUTO/GUIDED modes'''15314self.run_cmd(15315mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,15316p1=1, # 0: pause, 1: continue15317)1531815319def enum_state_name(self, enum_name, state, pretrim=None):15320e = mavutil.mavlink.enums[enum_name]15321e_value = e[state]15322name = e_value.name15323if pretrim is not None:15324if not pretrim.startswith(pretrim):15325raise NotAchievedException("Expected %s to pretrim" % (pretrim))15326name = name.replace(pretrim, "")15327return name1532815329def vtol_state_name(self, state):15330return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_")1533115332def landed_state_name(self, state):15333return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_")1533415335def assert_extended_sys_state(self, vtol_state, landed_state):15336m = self.assert_receive_message('EXTENDED_SYS_STATE')15337if m.vtol_state != vtol_state:15338raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" %15339(self.vtol_state_name(vtol_state),15340self.vtol_state_name(m.vtol_state)))15341if m.landed_state != landed_state:15342raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" %15343(self.landed_state_name(landed_state),15344self.landed_state_name(m.landed_state)))1534515346def wait_extended_sys_state(self, vtol_state, landed_state, timeout=10):15347tstart = self.get_sim_time()15348while True:15349if self.get_sim_time() - tstart > timeout:15350raise NotAchievedException("Did not achieve vol/landed states")15351self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" %15352(self.vtol_state_name(vtol_state),15353self.landed_state_name(landed_state)))15354m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True)15355if m.landed_state != landed_state:15356self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" %15357(self.landed_state_name(landed_state),15358self.landed_state_name(m.landed_state)))15359continue15360if m.vtol_state != vtol_state:15361self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" %15362(self.vtol_state_name(vtol_state),15363self.vtol_state_name(m.vtol_state)))15364continue1536515366self.progress("vtol and landed states match")15367return1536815369def setGCSfailsafe(self, paramValue):15370# Slow down the sim rate if GCS Failsafe is in use15371if paramValue == 0:15372self.set_parameters({15373"FS_GCS_ENABLE": paramValue,15374"SIM_SPEEDUP": 10,15375})15376else:15377self.set_parameters({15378"SIM_SPEEDUP": 4,15379"FS_GCS_ENABLE": paramValue,15380})1538115382def setup_servo_mount(self, roll_servo=5, pitch_servo=6, yaw_servo=7):15383'''configure a rpy servo mount; caller responsible for required rebooting'''15384self.progress("Setting up servo mount")15385self.set_parameters({15386"MNT1_TYPE": 1,15387"MNT1_PITCH_MIN": -45,15388"MNT1_PITCH_MAX": 45,15389"RC6_OPTION": 213, # MOUNT1_PITCH15390"SERVO%u_FUNCTION" % roll_servo: 8, # roll15391"SERVO%u_FUNCTION" % pitch_servo: 7, # pitch15392"SERVO%u_FUNCTION" % yaw_servo: 6, # yaw15393})153941539515396