Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/autotest/quadplane.py
Views: 1798
'''1Fly ArduPlane QuadPlane in SITL23AP_FLAKE8_CLEAN45'''67from __future__ import print_function8import os9import numpy10import math1112from pymavlink import mavutil13from pymavlink.rotmat import Vector31415import vehicle_test_suite16from vehicle_test_suite import Test17from vehicle_test_suite import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException1819import operator202122# get location of scripts23testdir = os.path.dirname(os.path.realpath(__file__))24WIND = "0,180,0.2" # speed,direction,variance25SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)262728class AutoTestQuadPlane(vehicle_test_suite.TestSuite):2930@staticmethod31def get_not_armable_mode_list():32return []3334@staticmethod35def get_not_disarmed_settable_modes_list():36return []3738@staticmethod39def get_no_position_not_settable_modes_list():40return []4142@staticmethod43def get_position_armable_modes_list():44return []4546@staticmethod47def get_normal_armable_modes_list():48return []4950def vehicleinfo_key(self):51return 'ArduPlane'5253def default_frame(self):54return "quadplane"5556def test_filepath(self):57return os.path.realpath(__file__)5859def sitl_start_location(self):60return SITL_START_LOCATION6162def default_speedup(self):63'''QuadPlane seems to be race-free'''64return 1006566def log_name(self):67return "QuadPlane"6869def set_current_test_name(self, name):70self.current_test_name_directory = "ArduPlane_Tests/" + name + "/"7172def apply_defaultfile_parameters(self):73# plane passes in a defaults_filepath in place of applying74# parameters afterwards.75pass7677def defaults_filepath(self):78return self.model_defaults_filepath(self.frame)7980def is_plane(self):81return True8283def get_stick_arming_channel(self):84return int(self.get_parameter("RCMAP_YAW"))8586def get_disarm_delay(self):87return int(self.get_parameter("LAND_DISARMDELAY"))8889def set_autodisarm_delay(self, delay):90self.set_parameter("LAND_DISARMDELAY", delay)9192def AirMode(self):93"""Check that plane.air_mode turns on and off as required"""94self.progress("########## Testing AirMode operation")95self.set_parameter("AHRS_EKF_TYPE", 10)96self.change_mode('QSTABILIZE')97self.wait_ready_to_arm()9899"""100SPIN_ARM and SPIN_MIN default to 0.10 and 0.15101when armed with zero throttle in AirMode, motor PWM should be at SPIN_MIN102If AirMode is off, motor PWM will drop to SPIN_ARM103"""104105self.progress("Verify that SERVO5 is Motor1 (default)")106motor1_servo_function_lp = 33107if (self.get_parameter('SERVO5_FUNCTION') != motor1_servo_function_lp):108raise PreconditionFailedException("SERVO5_FUNCTION not %d" % motor1_servo_function_lp)109110self.progress("Verify that flightmode channel is 5 (default)")111default_fltmode_ch = 5112if (self.get_parameter("FLTMODE_CH") != default_fltmode_ch):113raise PreconditionFailedException("FLTMODE_CH not %d" % default_fltmode_ch)114115"""When disarmed, motor PWM will drop to min_pwm"""116min_pwm = self.get_parameter("Q_M_PWM_MIN")117118self.progress("Verify Motor1 is at min_pwm when disarmed")119self.wait_servo_channel_value(5, min_pwm, comparator=operator.eq)120121armdisarm_option = 154122arm_ch = 8123self.set_parameter("RC%d_OPTION" % arm_ch, armdisarm_option)124self.progress("Configured RC%d as ARMDISARM switch" % arm_ch)125126"""arm with GCS, record Motor1 SPIN_ARM PWM output and disarm"""127spool_delay = self.get_parameter("Q_M_SPOOL_TIME") + 0.25128self.zero_throttle()129self.arm_vehicle()130self.progress("Waiting for Motor1 to spool up to SPIN_ARM")131self.delay_sim_time(spool_delay)132spin_arm_pwm = self.wait_servo_channel_value(5, min_pwm, comparator=operator.gt)133self.progress("spin_arm_pwm: %d" % spin_arm_pwm)134self.disarm_vehicle()135136"""arm with switch, record Motor1 SPIN_MIN PWM output and disarm"""137self.set_rc(8, 2000)138self.delay_sim_time(spool_delay)139self.progress("Waiting for Motor1 to spool up to SPIN_MIN")140spin_min_pwm = self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.gt)141self.progress("spin_min_pwm: %d" % spin_min_pwm)142self.set_rc(8, 1000)143144if (spin_arm_pwm >= spin_min_pwm):145raise PreconditionFailedException("SPIN_MIN pwm not greater than SPIN_ARM pwm")146147self.start_subtest("Test auxswitch arming with AirMode Switch")148for mode in ('QSTABILIZE', 'QACRO'):149"""verify that arming with switch results in higher PWM output"""150self.progress("Testing %s mode" % mode)151self.change_mode(mode)152self.zero_throttle()153self.progress("Arming with switch at zero throttle")154self.arm_motors_with_switch(arm_ch)155self.progress("Waiting for Motor1 to speed up")156self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)157158self.progress("Verify that rudder disarm is disabled")159try:160self.disarm_motors_with_rc_input()161except NotAchievedException:162pass163if not self.armed():164raise NotAchievedException("Rudder disarm not disabled")165166self.progress("Disarming with switch")167self.disarm_motors_with_switch(arm_ch)168self.progress("Waiting for Motor1 to stop")169self.wait_servo_channel_value(5, min_pwm, comparator=operator.le)170self.wait_ready_to_arm()171172self.start_subtest("Verify that arming with switch does not spin motors in other modes")173# disable compass magnetic field arming check that is triggered by the simulated lean of vehicle174# this is required because adjusting the AHRS_TRIM values only affects the IMU and not external compasses175arming_magthresh = self.get_parameter("ARMING_MAGTHRESH")176self.set_parameter("ARMING_MAGTHRESH", 0)177# introduce a large attitude error to verify that stabilization is not active178ahrs_trim_x = self.get_parameter("AHRS_TRIM_X")179self.set_parameter("AHRS_TRIM_X", math.radians(-60))180self.wait_roll(60, 1)181# test all modes except QSTABILIZE, QACRO, AUTO and QAUTOTUNE and QLAND and QRTL182# QRTL and QLAND aren't tested because we can't arm in that mode183for mode in (184'ACRO',185'AUTOTUNE',186'AVOID_ADSB',187'CIRCLE',188'CRUISE',189'FBWA',190'FBWB',191'GUIDED',192'LOITER',193'QHOVER',194'QLOITER',195'STABILIZE',196'TRAINING',197):198self.progress("Testing %s mode" % mode)199self.change_mode(mode)200self.zero_throttle()201self.progress("Arming with switch at zero throttle")202self.arm_motors_with_switch(arm_ch)203self.progress("Waiting for Motor1 to (not) speed up")204self.delay_sim_time(spool_delay)205self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.le)206self.wait_servo_channel_value(6, spin_arm_pwm, comparator=operator.le)207self.wait_servo_channel_value(7, spin_arm_pwm, comparator=operator.le)208self.wait_servo_channel_value(8, spin_arm_pwm, comparator=operator.le)209210self.progress("Disarming with switch")211self.disarm_motors_with_switch(arm_ch)212self.progress("Waiting for Motor1 to stop")213self.wait_servo_channel_value(5, min_pwm, comparator=operator.le)214self.wait_ready_to_arm()215# remove attitude error and reinstance compass arming check216self.set_parameter("AHRS_TRIM_X", ahrs_trim_x)217self.set_parameter("ARMING_MAGTHRESH", arming_magthresh)218219self.start_subtest("verify that AIRMODE auxswitch turns airmode on/off while armed")220"""set RC7_OPTION to AIRMODE"""221option_airmode = 84222self.set_parameter("RC7_OPTION", option_airmode)223224for mode in ('QSTABILIZE', 'QACRO'):225self.progress("Testing %s mode" % mode)226self.change_mode(mode)227self.zero_throttle()228self.progress("Arming with GCS at zero throttle")229self.arm_vehicle()230231self.progress("Turn airmode on with auxswitch")232self.set_rc(7, 2000)233self.progress("Waiting for Motor1 to speed up")234self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)235236self.progress("Turn airmode off with auxswitch")237self.set_rc(7, 1000)238self.progress("Waiting for Motor1 to slow down")239self.wait_servo_channel_value(5, spin_arm_pwm, comparator=operator.le)240self.disarm_vehicle()241self.wait_ready_to_arm()242243self.start_subtest("Test GCS arming")244for mode in ('QSTABILIZE', 'QACRO'):245self.progress("Testing %s mode" % mode)246self.change_mode(mode)247self.zero_throttle()248self.progress("Arming with GCS at zero throttle")249self.arm_vehicle()250251self.progress("Turn airmode on with auxswitch")252self.set_rc(7, 2000)253self.progress("Waiting for Motor1 to speed up")254self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)255256self.disarm_vehicle_expect_fail()257self.arm_vehicle()258259self.progress("Verify that airmode is still on")260self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)261self.disarm_vehicle(force=True)262self.wait_ready_to_arm()263264def TestMotorMask(self):265"""Check operation of output_motor_mask"""266"""copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)"""267if not (int(self.get_parameter('Q_TILT_MASK')) & 1):268self.progress("output_motor_mask not in use")269return270self.progress("Testing output_motor_mask")271self.wait_ready_to_arm()272273"""Default channel for Motor1 is 5"""274self.progress('Assert that SERVO5 is Motor1')275assert 33 == self.get_parameter('SERVO5_FUNCTION')276277modes = ('MANUAL', 'FBWA', 'QHOVER')278for mode in modes:279self.progress("Testing %s mode" % mode)280self.change_mode(mode)281self.arm_vehicle()282self.progress("Raising throttle")283self.set_rc(3, 1800)284self.progress("Waiting for Motor1 to start")285self.wait_servo_channel_value(5, 1100, comparator=operator.gt)286287self.set_rc(3, 1000)288self.disarm_vehicle()289self.wait_ready_to_arm()290291def fly_mission(self, filename, fence=None, height_accuracy=-1):292"""Fly a mission from a file."""293self.progress("Flying mission %s" % filename)294num_wp = self.load_mission(filename)295if self.mavproxy is not None:296self.mavproxy.send('wp list\n')297if fence is not None:298self.load_fence(fence)299if self.mavproxy is not None:300self.mavproxy.send('fence list\n')301# self.install_terrain_handlers_context()302self.change_mode('AUTO')303self.wait_ready_to_arm()304self.arm_vehicle()305self.wait_waypoint(1, num_wp-1)306self.wait_disarmed(timeout=120) # give quadplane a long time to land307308def EXTENDED_SYS_STATE_SLT(self):309self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10)310self.change_mode("QHOVER")311self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,312mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)313self.change_mode("FBWA")314self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,315mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)316self.change_mode("QHOVER")317318self.wait_ready_to_arm()319self.arm_vehicle()320321# should not change just because we arm:322self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,323mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)324self.change_mode("MANUAL")325self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,326mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND)327self.change_mode("QHOVER")328329self.progress("Taking off")330self.set_rc(3, 1750)331self.wait_altitude(1, 5, relative=True)332self.assert_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,333mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)334self.wait_altitude(10, 15, relative=True)335336self.progress("Transitioning to fixed wing")337self.change_mode("FBWA")338self.set_rc(3, 1900) # apply spurs339self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_TRANSITION_TO_FW,340mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)341self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_FW,342mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)343344self.progress("Transitioning to multicopter")345self.set_rc(3, 1500) # apply reins346self.change_mode("QHOVER")347# for a standard quadplane there is no transition-to-mc stage.348# tailsitters do have such a state.349self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,350mavutil.mavlink.MAV_LANDED_STATE_IN_AIR)351self.change_mode("QLAND")352self.wait_altitude(0, 2, relative=True, timeout=60)353self.wait_extended_sys_state(mavutil.mavlink.MAV_VTOL_STATE_MC,354mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,355timeout=30)356self.mav.motors_disarmed_wait()357358def EXTENDED_SYS_STATE(self):359'''Check extended sys state works'''360self.EXTENDED_SYS_STATE_SLT()361362def QAUTOTUNE(self):363'''test Plane QAutoTune mode'''364365# adjust tune so QAUTOTUNE can cope366self.set_parameters({367"Q_A_RAT_RLL_P" : 0.15,368"Q_A_RAT_RLL_I" : 0.25,369"Q_A_RAT_RLL_D" : 0.002,370"Q_A_RAT_PIT_P" : 0.15,371"Q_A_RAT_PIT_I" : 0.25,372"Q_A_RAT_PIT_D" : 0.002,373"Q_A_RAT_YAW_P" : 0.18,374"Q_A_RAT_YAW_I" : 0.018,375"Q_A_ANG_RLL_P" : 4.5,376"Q_A_ANG_PIT_P" : 4.5,377})378379# this is a list of all parameters modified by QAUTOTUNE. Set380# them so that when the context is popped we get the original381# values back:382parameter_values = self.get_parameters([383"Q_A_RAT_RLL_P",384"Q_A_RAT_RLL_I",385"Q_A_RAT_RLL_D",386"Q_A_ANG_RLL_P",387"Q_A_ACCEL_R_MAX",388"Q_A_RAT_PIT_P",389"Q_A_RAT_PIT_I",390"Q_A_RAT_PIT_D",391"Q_A_ANG_PIT_P",392"Q_A_ACCEL_P_MAX",393"Q_A_RAT_YAW_P",394"Q_A_RAT_YAW_I",395"Q_A_RAT_YAW_FLTE",396"Q_A_ANG_YAW_P",397"Q_A_ACCEL_Y_MAX",398])399self.set_parameters(parameter_values)400401self.takeoff(15, mode='GUIDED')402self.set_rc(3, 1500)403self.change_mode("QLOITER")404self.change_mode("QAUTOTUNE")405tstart = self.get_sim_time()406self.context_collect('STATUSTEXT')407while True:408now = self.get_sim_time_cached()409if now - tstart > 5000:410raise NotAchievedException("Did not get success message")411try:412self.wait_text("AutoTune: Success", timeout=1, check_context=True)413except AutoTestTimeoutException:414continue415# got success message416break417self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart))418self.context_clear_collection('STATUSTEXT')419420self.progress("Landing to save gains")421self.set_rc(3, 1200)422self.wait_speed_vector(423Vector3(float('nan'), float('nan'), 1.4),424timeout=5,425)426self.wait_speed_vector(427Vector3(0.0, 0.0, 0.0),428timeout=20,429)430distance = self.distance_to_home()431if distance > 20:432raise NotAchievedException("wandered from home (distance=%f)" %433(distance,))434self.set_rc(3, 1000)435tstart = self.get_sim_time()436while True:437now = self.get_sim_time_cached()438if now - tstart > 500:439raise NotAchievedException("Did not get success message")440self.send_mavlink_disarm_command()441try:442self.wait_text(443"AutoTune: Saved gains for Roll Pitch Yaw.*",444timeout=0.5,445check_context=True,446regex=True,447)448except AutoTestTimeoutException:449continue450break451452self.wait_disarmed()453self.reboot_sitl() # far from home454455def takeoff(self, height, mode, timeout=30):456"""climb to specified height and set throttle to 1500"""457self.set_current_waypoint(0, check_afterwards=False)458self.change_mode(mode)459self.wait_ready_to_arm()460self.arm_vehicle()461if mode == 'GUIDED':462self.user_takeoff(alt_min=height, timeout=timeout)463return464self.set_rc(3, 1800)465self.wait_altitude(height,466height+5,467relative=True,468timeout=timeout)469self.set_rc(3, 1500)470471def do_RTL(self):472self.change_mode("QRTL")473self.wait_altitude(-5, 1, relative=True, timeout=60)474self.wait_disarmed()475self.zero_throttle()476477def fly_home_land_and_disarm(self, timeout=30):478self.context_push()479self.change_mode('LOITER')480self.set_parameter('RTL_AUTOLAND', 2)481filename = "QuadPlaneDalbyRTL.txt"482self.progress("Using %s to fly home" % filename)483self.load_generic_mission(filename)484self.send_cmd_do_set_mode("RTL")485self.wait_mode('AUTO')486self.wait_current_waypoint(4)487self.wait_statustext('Land descend started')488self.wait_statustext('Land final started', timeout=60)489self.wait_disarmed(timeout=timeout)490self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)491# the following command is accepted, but doesn't actually492# work! Should be able to remove check_afterwards!493self.set_current_waypoint(0, check_afterwards=False)494self.change_mode('MANUAL')495self.context_pop()496497def wait_level_flight(self, accuracy=5, timeout=30):498"""Wait for level flight."""499tstart = self.get_sim_time()500self.progress("Waiting for level flight")501self.set_rc(1, 1500)502self.set_rc(2, 1500)503self.set_rc(4, 1500)504while self.get_sim_time_cached() < tstart + timeout:505m = self.mav.recv_match(type='ATTITUDE', blocking=True)506roll = math.degrees(m.roll)507pitch = math.degrees(m.pitch)508self.progress("Roll=%.1f Pitch=%.1f" % (roll, pitch))509if math.fabs(roll) <= accuracy and math.fabs(pitch) <= accuracy:510self.progress("Attained level flight")511return512raise NotAchievedException("Failed to attain level flight")513514def fly_left_circuit(self):515"""Fly a left circuit, 200m on a side."""516self.mavproxy.send('switch 4\n')517self.change_mode('FBWA')518self.set_rc(3, 1700)519self.wait_level_flight()520521self.progress("Flying left circuit")522# do 4 turns523for i in range(0, 4):524# hard left525self.progress("Starting turn %u" % i)526self.set_rc(1, 1000)527self.wait_heading(270 - (90*i), accuracy=10)528self.set_rc(1, 1500)529self.progress("Starting leg %u" % i)530self.wait_distance(100, accuracy=20)531self.progress("Circuit complete")532self.change_mode('QHOVER')533self.set_rc(3, 1100)534self.wait_altitude(10, 15,535relative=True,536timeout=60)537self.set_rc(3, 1500)538539def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, fftLength=32, peakhz=None):540541# find a motor peak542self.takeoff(10, mode="QHOVER")543544hover_time = 15545tstart = self.get_sim_time()546self.progress("Hovering for %u seconds" % hover_time)547while self.get_sim_time_cached() < tstart + hover_time:548self.mav.recv_match(type='ATTITUDE', blocking=True)549vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True)550tend = self.get_sim_time()551552self.do_RTL()553psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)554555# batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin556scale = 1000. / 1024.557sminhz = int(minhz * scale)558smaxhz = int(maxhz * scale)559freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz]560peakdb = numpy.amax(psd["X"][sminhz:smaxhz])561if peakdb < dblevel or (peakhz is not None and abs(freq - peakhz) / peakhz > 0.05):562raise NotAchievedException("No motor peak, found %fHz at %fdB" % (freq, peakdb))563else:564self.progress("motor peak %fHz, thr %f%%, %fdB" % (freq, vfr_hud.throttle, peakdb))565566# we have a peak make sure that the FFT detected something close567# logging is at 10Hz568mlog = self.dfreader_for_current_onboard_log()569# accuracy is determined by sample rate and fft length, given our use of quinn we could probably use half of this570freqDelta = 1000. / fftLength571pkAvg = freq572freqs = []573574while True:575m = mlog.recv_match(576type='FTN1',577blocking=True,578condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6))579if m is None:580break581freqs.append(m.PkAvg)582583# peak within resolution of FFT length584pkAvg = numpy.median(numpy.asarray(freqs))585if abs(pkAvg - freq) > freqDelta:586raise NotAchievedException("FFT did not detect a motor peak at %f, found %f, wanted %f" % (dblevel, pkAvg, freq))587588return freq589590def GyroFFT(self):591"""Use dynamic harmonic notch to control motor noise."""592# basic gyro sample rate test593self.progress("Flying with gyro FFT - Gyro sample rate")594self.context_push()595ex = None596try:597self.set_rc_default()598599# magic tridge EKF type that dramatically speeds up the test600self.set_parameters({601"AHRS_EKF_TYPE": 10,602603"INS_LOG_BAT_MASK": 3,604"INS_LOG_BAT_OPT": 0,605"INS_GYRO_FILTER": 100,606"LOG_BITMASK": 45054,607"LOG_DISARMED": 0,608"SIM_DRIFT_SPEED": 0,609"SIM_DRIFT_TIME": 0,610# enable a noisy motor peak611"SIM_GYR1_RND": 20,612# enabling FFT will also enable the arming check: self-testing the functionality613"FFT_ENABLE": 1,614"FFT_MINHZ": 80,615"FFT_MAXHZ": 350,616"FFT_SNR_REF": 10,617"FFT_WINDOW_SIZE": 128,618"FFT_WINDOW_OLAP": 0.75,619})620# Step 1: inject a very precise noise peak at 250hz and make sure the in-flight fft621# can detect it really accurately. For a 128 FFT the frequency resolution is 8Hz so622# a 250Hz peak should be detectable within 5%623self.set_parameters({624"SIM_VIB_FREQ_X": 250,625"SIM_VIB_FREQ_Y": 250,626"SIM_VIB_FREQ_Z": 250,627})628self.reboot_sitl()629630# find a motor peak631self.hover_and_check_matched_frequency(-15, 100, 350, 128, 250)632633# Step 2: inject actual motor noise and use the standard length FFT to track it634self.set_parameters({635"SIM_VIB_MOT_MAX": 350,636"FFT_WINDOW_SIZE": 32,637"FFT_WINDOW_OLAP": 0.5,638})639self.reboot_sitl()640# find a motor peak641freq = self.hover_and_check_matched_frequency(-15, 200, 300, 32)642643# Step 3: add a FFT dynamic notch and check that the peak is squashed644self.set_parameters({645"INS_LOG_BAT_OPT": 2,646"INS_HNTCH_ENABLE": 1,647"INS_HNTCH_FREQ": freq,648"INS_HNTCH_REF": 1.0,649"INS_HNTCH_ATT": 50,650"INS_HNTCH_BW": freq/2,651"INS_HNTCH_MODE": 4,652})653self.reboot_sitl()654655self.takeoff(10, mode="QHOVER")656hover_time = 15657ignore_bins = 20658659self.progress("Hovering for %u seconds" % hover_time)660tstart = self.get_sim_time()661while self.get_sim_time_cached() < tstart + hover_time:662self.mav.recv_match(type='ATTITUDE', blocking=True)663tend = self.get_sim_time()664665self.do_RTL()666psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6)667freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins]668peakdB = numpy.amax(psd["X"][ignore_bins:])669if peakdB < -10:670self.progress("No motor peak, %f at %f dB" % (freq, peakdB))671else:672raise NotAchievedException("Detected peak at %f Hz of %.2f dB" % (freq, peakdB))673674# Step 4: take off as a copter land as a plane, make sure we track675self.progress("Flying with gyro FFT - vtol to plane")676self.load_mission("quadplane-gyro-mission.txt")677if self.mavproxy is not None:678self.mavproxy.send('wp list\n')679self.change_mode('AUTO')680self.wait_ready_to_arm()681self.arm_vehicle()682self.wait_waypoint(1, 7, max_dist=60, timeout=1200)683self.wait_disarmed(timeout=120) # give quadplane a long time to land684685# prevent update parameters from messing with the settings when we pop the context686self.set_parameter("FFT_ENABLE", 0)687self.reboot_sitl()688689except Exception as e:690self.progress("Exception caught: %s" % (691self.get_exception_stacktrace(e)))692ex = e693694self.context_pop()695696self.reboot_sitl()697698if ex is not None:699raise ex700701def PIDTuning(self):702'''Test PID Tuning'''703self.change_mode("FBWA") # we don't update PIDs in MANUAL704super(AutoTestQuadPlane, self).PIDTuning()705706def ParameterChecks(self):707'''basic parameter checks'''708self.test_parameter_checks_poscontrol("Q_P")709710def rc_defaults(self):711ret = super(AutoTestQuadPlane, self).rc_defaults()712ret[3] = 1000713return ret714715def default_mode(self):716return "MANUAL"717718def disabled_tests(self):719return {720"FRSkyPassThrough": "Currently failing",721"CPUFailsafe": "servo channel values not scaled like ArduPlane",722"GyroFFT": "flapping test",723"ConfigErrorLoop": "failing because RC values not settable",724}725726def BootInAUTO(self):727'''Test behaviour when booting in auto'''728self.load_mission("mission.txt")729self.set_parameters({730})731self.set_rc(5, 1000)732self.wait_mode('AUTO')733self.reboot_sitl()734self.wait_ready_to_arm()735self.delay_sim_time(20)736self.assert_current_waypoint(1)737self.arm_vehicle()738self.wait_altitude(9, 11, relative=True) # value from mission file is 10739distance = self.distance_to_home()740# this distance check is very, very loose. At time of writing741# the vehicle actually pitches ~6 degrees on trakeoff,742# wandering over 1m.743if distance > 2:744raise NotAchievedException("wandered from home (distance=%f)" %745(distance,))746self.change_mode('QLAND')747self.wait_disarmed(timeout=60)748749def PilotYaw(self):750'''Test pilot yaw in various modes'''751self.takeoff(10, mode="QLOITER")752self.set_parameter("STICK_MIXING", 0)753self.set_rc(4, 1700)754for mode in "QLOITER", "QHOVER":755self.wait_heading(45)756self.wait_heading(90)757self.wait_heading(180)758self.wait_heading(275)759self.set_rc(4, 1500)760self.do_RTL()761762def FwdThrInVTOL(self):763'''test use of fwd motor throttle into wind'''764self.set_parameters({"SIM_WIND_SPD": 25, # need very strong wind for this test765"SIM_WIND_DIR": 360,766"Q_WVANE_ENABLE": 1,767"Q_WVANE_GAIN": 1,768"STICK_MIXING": 0,769"Q_FWD_THR_USE": 2})770771self.takeoff(10, mode="QLOITER")772self.set_rc(2, 1000)773self.delay_sim_time(10)774# Check that it is using some forward throttle775fwd_thr_pwm = self.get_servo_channel_value(3)776if fwd_thr_pwm < 1150 :777raise NotAchievedException("fwd motor pwm command low, want >= 1150 got %f" % (fwd_thr_pwm))778# check that pitch is on limit779m = self.mav.recv_match(type='ATTITUDE', blocking=True)780pitch = math.degrees(m.pitch)781if abs(pitch + 3.0) > 0.5 :782raise NotAchievedException("pitch should be -3.0 +- 0.5 deg, got %f" % (pitch))783self.set_rc(2, 1500)784self.delay_sim_time(5)785loc1 = self.mav.location()786self.set_parameter("SIM_ENGINE_FAIL", 1 << 2) # simulate a complete loss of forward motor thrust787self.delay_sim_time(20)788self.change_mode('QLAND')789self.wait_disarmed(timeout=60)790loc2 = self.mav.location()791position_drift = self.get_distance(loc1, loc2)792if position_drift > 5.0 :793raise NotAchievedException("position drift high, want < 5.0 m got %f m" % (position_drift))794795def Weathervane(self):796'''test nose-into-wind functionality'''797# We test nose into wind code paths and yaw direction in copter autotest,798# so we shall test the side into wind yaw direction and plane code paths here.799self.set_parameters({"SIM_WIND_SPD": 10,800"SIM_WIND_DIR": 240,801"Q_WVANE_ENABLE": 3, # WVANE_ENABLE = 3 gives direction of side into wind802"Q_WVANE_GAIN": 3,803"STICK_MIXING": 0})804805self.takeoff(10, mode="QLOITER")806807# Turn aircraft to heading 90 deg808self.set_rc(4, 1700)809self.wait_heading(90)810self.set_rc(4, 1500)811812# Now wait for weathervaning to activate and turn side-on to wind at 240 deg therefore heading 150 deg813self.wait_heading(150, accuracy=5, timeout=180)814815self.do_RTL()816817def CPUFailsafe(self):818'''In lockup Plane should copy RC inputs to RC outputs'''819self.plane_CPUFailsafe()820821def QAssist(self):822'''QuadPlane Assist tests'''823self.takeoff(10, mode="QHOVER")824self.set_rc(3, 1800)825self.change_mode("FBWA")826827# disable stall prevention so roll angle is not limited828self.set_parameter("STALL_PREVENTION", 0)829830thr_min_pwm = self.get_parameter("Q_M_PWM_MIN")831lim_roll_deg = self.get_parameter("ROLL_LIMIT_DEG")832self.progress("Waiting for motors to stop (transition completion)")833self.wait_servo_channel_value(5,834thr_min_pwm,835timeout=30,836comparator=operator.eq)837self.delay_sim_time(5)838self.wait_servo_channel_value(5,839thr_min_pwm,840timeout=30,841comparator=operator.eq)842self.progress("Stopping forward motor to kill airspeed below limit")843self.set_rc(3, 1000)844self.progress("Waiting for qassist to kick in")845self.wait_servo_channel_value(5, 1400, timeout=30, comparator=operator.gt)846self.progress("Move forward again, check qassist stops")847self.set_rc(3, 1800)848self.progress("Checking qassist stops")849self.wait_servo_channel_value(5,850thr_min_pwm,851timeout=30,852comparator=operator.eq)853self.set_rc(3, 1300)854855# Test angle assist856self.context_push()857self.progress("Rolling over to %.0f degrees" % -lim_roll_deg)858self.set_rc(1, 1000)859self.wait_roll(-lim_roll_deg, 5)860self.progress("Killing servo outputs to force qassist to help")861self.set_parameter("SERVO1_MIN", 1480)862self.set_parameter("SERVO1_MAX", 1480)863self.set_parameter("SERVO1_TRIM", 1480)864self.progress("Trying to roll over hard the other way")865self.set_rc(1, 2000)866self.progress("Waiting for qassist (angle) to kick in")867self.wait_servo_channel_value(5, 1100, timeout=30, comparator=operator.gt)868self.wait_roll(lim_roll_deg, 5)869self.context_pop()870self.set_rc(1, 1500)871872# Test alt assist, climb to 60m and set assist alt to 50m873self.context_push()874guided_loc = self.home_relative_loc_ne(0, 0)875guided_loc.alt = 60876self.change_mode("GUIDED")877self.send_do_reposition(guided_loc)878self.wait_altitude(58, 62, relative=True)879self.set_parameter("Q_ASSIST_ALT", 50)880881# Try and descent to 40m882guided_loc.alt = 40883self.send_do_reposition(guided_loc)884885# Expect alt assist to kick in, eg "Alt assist 48.9m"886self.wait_statustext(r"Alt assist \d*.\d*m", regex=True, timeout=100)887888# Test transition timeout, should switch to QRTL889self.set_parameter("Q_TRANS_FAIL_ACT", 1)890self.set_parameter("Q_TRANS_FAIL", 10)891self.wait_mode("QRTL")892893self.context_pop()894895self.wait_disarmed(timeout=200)896897def LoiterAltQLand(self):898'''test loitering and qland with terrain involved'''899self.LoiterAltQLand_Terrain(900home="LakeGeorgeLookout",901ofs_n=0,902ofs_e=300,903)904# self.LoiterAltQLand_Terrain(905# home="KalaupapaCliffs",906# ofs_n=500,907# ofs_e=500,908# )909self.LoiterAltQLand_Relative()910911def LoiterAltQLand_Relative(self):912'''test failsafe where vehicle loiters in fixed-wing mode to a913specific altitude then changes mode to QLAND'''914self.set_parameters({915'BATT_MONITOR': 4, # LoiterAltQLand916'BATT_FS_LOW_ACT': 6, # LoiterAltQLand917})918self.reboot_sitl()919takeoff_alt = 5920self.takeoff(takeoff_alt, mode='QLOITER')921loc = self.mav.location()922self.location_offset_ne(loc, 500, 500)923new_alt = 100924initial_altitude = self.get_altitude(relative=False, timeout=2)925self.run_cmd_int(926mavutil.mavlink.MAV_CMD_DO_REPOSITION,9270,9281, # reposition flags; 1 means "change to guided"9290,9300,931int(loc.lat * 1e7),932int(loc.lng * 1e7),933new_alt, # alt934frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,935)936self.wait_altitude(937new_alt-1,938new_alt+1,939timeout=60,940relative=True,941minimum_duration=10)942self.wait_location(loc, timeout=120, accuracy=100)943self.progress("Triggering failsafe")944self.set_parameter('BATT_LOW_VOLT', 50)945self.wait_mode(25) # LoiterAltQLand946self.drain_mav()947m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)948q_rtl_alt = self.get_parameter('Q_RTL_ALT')949expected_alt = initial_altitude - takeoff_alt + q_rtl_alt950951if abs(m.alt - expected_alt) > 20:952raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %953(expected_alt, m.alt))954self.assert_mode('LOITERALTQLAND')955self.wait_mode('QLAND')956alt = self.get_altitude(relative=True)957if abs(alt - q_rtl_alt) > 2:958raise NotAchievedException("qland too late; want=%f got=%f" %959(alt, q_rtl_alt))960961self.wait_disarmed(timeout=300)962963def LoiterAltQLand_Terrain(self,964home=None,965ofs_n=None,966ofs_e=None,967reposition_alt=100):968'''test failsafe where vehicle loiters in fixed-wing mode to a969specific altitude then changes mode to QLAND'''970self.context_push()971self.install_terrain_handlers_context()972self.set_parameters({973'BATT_MONITOR': 4, # LoiterAltQLand974'BATT_FS_LOW_ACT': 6, # LoiterAltQLand975'TERRAIN_FOLLOW': 1, # enabled in all modes976})977self.customise_SITL_commandline(978["--home", home]979)980takeoff_alt = 5981self.takeoff(takeoff_alt, mode='QLOITER')982loc = self.mav.location()983self.location_offset_ne(loc, ofs_n, ofs_e)984initial_altitude = self.get_altitude(relative=False, timeout=2)985self.run_cmd_int(986mavutil.mavlink.MAV_CMD_DO_REPOSITION,9870,9881, # reposition flags; 1 means "change to guided"9890,9900,991int(loc.lat * 1e7),992int(loc.lng * 1e7),993reposition_alt, # alt994frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,995)996self.wait_altitude(997reposition_alt-1,998reposition_alt+1,999timeout=60,1000relative=True,1001minimum_duration=10)10021003self.wait_location(loc, timeout=500, accuracy=100)10041005self.progress("Triggering failsafe")1006self.set_parameter('BATT_LOW_VOLT', 50)1007self.wait_mode(25) # LoiterAltQLand1008terrain_alt = self.get_terrain_height(verbose=True)1009self.drain_mav()1010m = self.assert_receive_message('POSITION_TARGET_GLOBAL_INT', very_verbose=True)1011q_rtl_alt = self.get_parameter('Q_RTL_ALT')1012expected_alt = terrain_alt + q_rtl_alt10131014if abs(m.alt - expected_alt) > 20:1015raise NotAchievedException("Unexpected altitude; expected=%f got=%f" %1016(expected_alt, m.alt))1017self.assert_mode('LOITERALTQLAND')1018self.wait_mode('QLAND')1019alt = initial_altitude + self.get_altitude(relative=True)1020if abs(alt - expected_alt) > 10:1021raise NotAchievedException("qland too late; want=%f got=%f" %1022(expected_alt, alt))10231024self.wait_disarmed(timeout=300)1025self.zero_throttle()1026self.reset_SITL_commandline()1027self.context_pop()10281029def GUIDEDToAUTO(self):1030'''Test using GUIDED mode for takeoff before shifting to auto'''1031self.load_mission("mission.txt")1032self.takeoff(30, mode='GUIDED')10331034# extra checks would go here1035self.assert_not_receiving_message('CAMERA_FEEDBACK')10361037self.change_mode('AUTO')1038self.wait_current_waypoint(3)1039self.change_mode('QRTL')1040self.wait_disarmed(timeout=240)10411042def Tailsitter(self):1043'''tailsitter test'''1044self.set_parameter('Q_FRAME_CLASS', 10)1045self.set_parameter('Q_ENABLE', 1)1046self.set_parameter('Q_TAILSIT_ENABLE', 1)10471048self.reboot_sitl()1049self.wait_ready_to_arm()1050value_before = self.get_servo_channel_value(3)1051self.progress("Before: %u" % value_before)1052self.change_mode('QHOVER')1053tstart = self.get_sim_time()1054while True:1055now = self.get_sim_time_cached()1056if now - tstart > 60:1057break1058value_after = self.get_servo_channel_value(3)1059self.progress("After: t=%f output=%u" % ((now - tstart), value_after))1060if value_before != value_after:1061raise NotAchievedException("Changed throttle output on mode change to QHOVER")1062self.disarm_vehicle()10631064def CopterTailsitter(self):1065'''copter tailsitter test'''1066self.customise_SITL_commandline(1067[],1068defaults_filepath=self.model_defaults_filepath('quadplane-copter_tailsitter'),1069model="quadplane-copter_tailsitter",1070wipe=True,1071)10721073self.reboot_sitl()1074self.wait_ready_to_arm()1075self.takeoff(60, mode='GUIDED')1076self.context_collect("STATUSTEXT")1077self.progress("Starting QLAND")1078self.change_mode("QLAND")1079self.wait_statustext("Rangefinder engaged")1080self.wait_disarmed(timeout=100)10811082def setup_ICEngine_vehicle(self):1083'''restarts SITL with an IC Engine setup'''1084model = "quadplane-ice"1085self.customise_SITL_commandline(1086[],1087model=model,1088defaults_filepath=self.model_defaults_filepath(model),1089wipe=False,1090)10911092def ICEngine(self):1093'''Test ICE Engine support'''1094rc_engine_start_chan = 111095self.setup_ICEngine_vehicle()10961097self.wait_ready_to_arm()1098self.wait_rpm(1, 0, 0, minimum_duration=1)1099self.arm_vehicle()1100self.wait_rpm(1, 0, 0, minimum_duration=1)1101self.context_collect("STATUSTEXT")1102self.progress("Setting engine-start RC switch to HIGH")1103self.set_rc(rc_engine_start_chan, 2000)1104self.wait_statustext("Starting engine", check_context=True)1105self.wait_rpm(1, 300, 400, minimum_duration=1)1106self.progress("Setting engine-start RC switch to MID")1107self.set_rc(rc_engine_start_chan, 1500)1108self.progress("Setting full throttle")1109self.set_rc(3, 2000)1110self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40)1111self.progress("Setting min-throttle")1112self.set_rc(3, 1000)1113self.wait_rpm(1, 65, 75, minimum_duration=1)1114self.progress("Setting engine-start RC switch to LOW")1115self.set_rc(rc_engine_start_chan, 1000)1116self.wait_rpm(1, 0, 0, minimum_duration=1)1117# ICE provides forward thrust, which can make us think we're flying:1118self.disarm_vehicle(force=True)1119self.reboot_sitl()11201121self.start_subtest("Testing throttle out in manual mode")1122self.change_mode('MANUAL')1123self.set_rc(3, 1700)1124self.wait_servo_channel_value(3, 2000)1125self.set_parameter("ICE_OPTIONS", 4)1126# remember that throttle is reversed!1127self.wait_servo_channel_value(3, 1300)1128self.change_mode('FBWA')1129self.wait_servo_channel_value(3, 2000)11301131self.start_subtest("Testing automatic restart")1132# Limit start attempts to 41133max_tries = 41134self.set_parameter("ICE_STRT_MX_RTRY", max_tries)1135# Make the engine unable to run (by messing up the RPM sensor)1136rpm_chan = self.get_parameter("ICE_RPM_CHAN")1137self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor1138self.set_rc(rc_engine_start_chan, 2000)1139self.wait_statustext("Uncommanded engine stop")1140self.wait_statustext("Starting engine")1141# Restore the engine1142self.set_parameter("ICE_RPM_CHAN", rpm_chan)1143# Make sure the engine continues to run for the next 30 seconds1144try:1145self.wait_statustext("Uncommanded engine stop", timeout=30)1146# The desired result is for the wait_statustext raise AutoTestTimeoutException1147raise NotAchievedException("Engine stopped unexpectedly")1148except AutoTestTimeoutException:1149pass1150self.context_stop_collecting("STATUSTEXT")11511152self.start_subtest("Testing automatic starter attempt limit")1153# Try this test twice.1154# For the first run, since the engine has been running successfully in1155# the previous test for 30 seconds, the limit should reset. For the1156# second run, after commanding an engine stop, the limit should reset.1157for i in range(2):1158self.context_collect("STATUSTEXT")1159self.set_parameter("ICE_RPM_CHAN", 120) # Set to a non-existent sensor1160self.set_rc(rc_engine_start_chan, 2000)1161self.wait_statustext("Engine max crank attempts reached", check_context=True, timeout=30)1162self.delay_sim_time(30) # wait for another 30 seconds to make sure the engine doesn't restart1163messages = self.context_get().collections["STATUSTEXT"]1164self.context_stop_collecting("STATUSTEXT")1165# check for the exact number of starter attempts1166attempts = 01167for m in messages:1168if "Starting engine" == m.text:1169attempts += 11170if attempts != max_tries:1171raise NotAchievedException(f"Run {i+1}: Expected {max_tries} attempts, got {attempts}")1172# Command an engine stop1173self.context_collect("STATUSTEXT")1174self.set_rc(rc_engine_start_chan, 1000)1175self.wait_statustext("ignition:0", check_context=True)1176self.context_stop_collecting("STATUSTEXT")11771178def ICEngineMission(self):1179'''Test ICE Engine Mission support'''1180rc_engine_start_chan = 111181self.setup_ICEngine_vehicle()11821183self.load_mission("mission.txt")1184self.wait_ready_to_arm()1185self.set_rc(rc_engine_start_chan, 2000)1186self.arm_vehicle()1187self.change_mode('AUTO')1188self.wait_disarmed(timeout=300)11891190def MAV_CMD_DO_ENGINE_CONTROL(self):1191'''test MAV_CMD_DO_ENGINE_CONTROL mavlink command'''11921193expected_idle_rpm_min = 651194expected_idle_rpm_max = 751195expected_starter_rpm_min = 3451196expected_starter_rpm_max = 35511971198rc_engine_start_chan = 111199self.setup_ICEngine_vehicle()12001201self.wait_ready_to_arm()12021203for method in self.run_cmd, self.run_cmd_int:1204self.change_mode('MANUAL')1205self.set_rc(rc_engine_start_chan, 1500) # allow motor to run1206self.wait_rpm(1, 0, 0, minimum_duration=1)1207self.arm_vehicle()1208self.wait_rpm(1, 0, 0, minimum_duration=1)1209self.start_subtest("Start motor")1210method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1)1211self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max)1212self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=10)12131214# starting the motor while it is running is failure1215# (probably wrong, but that's how this works):1216self.start_subtest("try start motor again")1217self.context_collect('STATUSTEXT')1218method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)1219self.wait_statustext("already running", check_context=True)1220self.context_stop_collecting('STATUSTEXT')1221# shouldn't affect run state:1222self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=1)12231224self.start_subtest("Stop motor")1225method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)1226self.wait_rpm(1, 0, 0, minimum_duration=1)12271228self.start_subtest("Stop motor (again)")1229method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)1230self.wait_rpm(1, 0, 0, minimum_duration=1)12311232self.start_subtest("Check start chan control disable")1233old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan)1234self.set_rc(rc_engine_start_chan, 1000)1235self.delay_sim_time(1) # Make sure the RC change has registered1236self.context_collect('STATUSTEXT')1237method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)1238self.wait_statustext("start control disabled", check_context=True)1239self.context_stop_collecting('STATUSTEXT')1240self.set_rc(rc_engine_start_chan, old_start_channel_value)1241self.wait_rpm(1, 0, 0, minimum_duration=1)12421243self.start_subtest("test start-at-height")1244self.wait_rpm(1, 0, 0, minimum_duration=1)1245self.context_collect('STATUSTEXT')1246method(1247mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL,1248p1=1, # start1249p3=15.5, # ... at 15.5 metres1250)1251self.wait_statustext("height set to 15.5m", check_context=True)1252self.wait_rpm(1, 0, 0, minimum_duration=2)12531254self.takeoff(20, mode='GUIDED')1255self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max, minimum_duration=1)1256self.wait_statustext("Engine running", check_context=True)1257self.context_stop_collecting('STATUSTEXT')12581259# stop the motor again:1260method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0)1261self.wait_rpm(1, 0, 0, minimum_duration=1)12621263self.change_mode('QLAND')1264self.wait_disarmed()12651266def Ship(self):1267'''Ensure we can take off from simulated ship'''1268self.context_push()1269self.set_parameters({1270'SIM_SHIP_ENABLE': 1,1271'SIM_SHIP_SPEED': 1, # the default of 3 will break this test1272})1273self.change_mode('QLOITER')1274self.wait_ready_to_arm()1275self.arm_vehicle()1276self.set_rc(3, 1700)1277# self.delay_sim_time(1)1278# self.send_debug_trap()1279# output here is a bit weird as we also receive altitude from1280# the simulated ship....1281self.wait_altitude(20, 30, relative=True)1282self.disarm_vehicle(force=True)1283self.context_pop()1284self.reboot_sitl()12851286def MidAirDisarmDisallowed(self):1287'''Check disarm behaviour in Q-mode'''1288self.start_subtest("Basic arm in qloiter")1289self.set_parameter("FLIGHT_OPTIONS", 0)1290self.change_mode('QLOITER')1291self.wait_ready_to_arm()1292self.arm_vehicle()1293self.disarm_vehicle()12941295self.context_push()1296self.start_subtest("Ensure disarming in q-modes on ground works")1297self.set_parameter("FLIGHT_OPTIONS", 1 << 11)1298self.arm_vehicle()1299self.disarm_vehicle() # should be OK as we're not flying yet1300self.context_pop()13011302self.start_subtest("Ensure no disarming mid-air")1303self.arm_vehicle()1304self.set_rc(3, 2000)1305self.wait_altitude(5, 50, relative=True)1306self.set_rc(3, 1000)1307disarmed = False1308try:1309self.disarm_vehicle()1310disarmed = True1311except ValueError as e:1312self.progress("Got %s" % repr(e))1313if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e):1314raise e1315if disarmed:1316raise NotAchievedException("Disarmed when we shouldn't have")13171318self.change_mode('QLAND')1319self.wait_disarmed()13201321self.start_subtest("Check we can disarm after a short period on the ground")1322self.takeoff(5, 'QHOVER')1323self.change_mode('QLAND')1324try:1325self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10)1326self.wait_extended_sys_state(1327landed_state=mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND,1328vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC,1329timeout=601330)1331except Exception:1332self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 0)1333raise13341335self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1)1336self.disarm_vehicle()13371338def MAV_CMD_NAV_LOITER_TO_ALT(self, target_system=1, target_component=1):1339'''ensure consecutive loiter to alts work'''1340self.load_mission('mission.txt')1341self.change_mode('AUTO')1342self.wait_ready_to_arm()1343self.arm_vehicle()1344self.wait_current_waypoint(4, timeout=240)1345self.assert_altitude(120, accuracy=5, relative=True)1346self.delay_sim_time(30)1347self.assert_altitude(120, accuracy=5, relative=True)1348self.set_current_waypoint(5)1349self.wait_altitude(altitude_min=65, altitude_max=75, relative=True)1350if self.current_waypoint() != 5:1351raise NotAchievedException("Should pass 90m before passing waypoint 5")1352self.wait_disarmed(timeout=300)13531354def Mission(self):1355'''fly the OBC 2016 mission in Dalby'''1356self.load_mission("Dalby-OBC2016.txt")1357self.load_fence("Dalby-OBC2016-fence.txt")1358if self.mavproxy is not None:1359self.mavproxy.send('wp list\n')1360self.install_terrain_handlers_context()1361self.wait_ready_to_arm()1362self.arm_vehicle()1363self.change_mode('AUTO')1364self.wait_waypoint(1, 19, max_dist=60, timeout=1200)13651366self.wait_disarmed(timeout=120) # give quadplane a long time to land1367# wait for blood sample here1368self.set_current_waypoint(20)1369self.wait_ready_to_arm()1370self.arm_vehicle()1371self.wait_waypoint(20, 34, max_dist=60, timeout=1200)13721373self.wait_disarmed(timeout=120) # give quadplane a long time to land1374self.progress("Mission OK")13751376def VTOLLandSpiral(self):1377'''check spiral-to-alt option for landing'''1378self.fly_mission('mission.txt')1379self.set_parameter('WP_LOITER_RAD', -self.get_parameter('WP_LOITER_RAD'))1380self.set_current_waypoint(0, check_afterwards=False)1381self.fly_mission('mission.txt')13821383def VTOLQuicktune(self):1384'''VTOL Quicktune'''1385self.install_applet_script_context("VTOL-quicktune.lua")13861387self.set_parameters({1388"SCR_ENABLE": 1,1389"SIM_SPEEDUP": 20, # need to give some cycles to lua1390"RC7_OPTION": 300,1391})13921393self.reboot_sitl()13941395self.context_collect('STATUSTEXT')1396self.set_parameters({1397"QUIK_ENABLE" : 1,1398"QUIK_DOUBLE_TIME" : 5, # run faster for autotest1399})14001401self.scripting_restart()1402self.wait_text("Quicktune for quadplane loaded", check_context=True)14031404self.wait_ready_to_arm()1405self.change_mode("QLOITER")1406self.arm_vehicle()1407self.takeoff(20, 'QLOITER')14081409# use rc switch to start tune1410self.set_rc(7, 1500)14111412self.wait_text("Tuning: starting tune", check_context=True)1413for axis in ['RLL', 'PIT', 'YAW']:1414self.wait_text("Starting %s tune" % axis, check_context=True)1415self.wait_text("Tuning: %s_D done" % axis, check_context=True, timeout=120)1416self.wait_text("Tuning: %s_P done" % axis, check_context=True, timeout=120)1417self.wait_text("Tuning: %s done" % axis, check_context=True, timeout=120)1418self.wait_text("Tuning: YAW done", check_context=True, timeout=120)14191420# to test aux function method, use aux fn for save1421self.run_auxfunc(300, 2)1422self.wait_text("Tuning: saved", check_context=True)1423self.change_mode("QLAND")14241425self.wait_disarmed(timeout=120)14261427def VTOLQuicktune_CPP(self):1428'''VTOL Quicktune in C++'''1429self.set_parameters({1430"RC7_OPTION": 181,1431"QWIK_ENABLE" : 1,1432"QWIK_DOUBLE_TIME" : 5, # run faster for autotest1433})14341435self.context_push()1436self.context_collect('STATUSTEXT')14371438# reduce roll/pitch gains by 21439gain_mul = 0.51440soften_params = ['Q_A_RAT_RLL_P', 'Q_A_RAT_RLL_I', 'Q_A_RAT_RLL_D',1441'Q_A_RAT_PIT_P', 'Q_A_RAT_PIT_I', 'Q_A_RAT_PIT_D',1442'Q_A_RAT_YAW_P', 'Q_A_RAT_YAW_I']14431444original_values = self.get_parameters(soften_params)14451446softened_values = {}1447for p in original_values.keys():1448softened_values[p] = original_values[p] * gain_mul1449self.set_parameters(softened_values)14501451self.wait_ready_to_arm()1452self.change_mode("QLOITER")1453self.set_rc(7, 1000)1454self.arm_vehicle()1455self.takeoff(20, 'QLOITER')14561457# use rc switch to start tune1458self.set_rc(7, 1500)14591460self.wait_text("Quicktune: starting tune", check_context=True)1461for axis in ['Roll', 'Pitch', 'Yaw']:1462self.wait_text("Starting %s tune" % axis, check_context=True)1463self.wait_text("Quicktune: %s D done" % axis, check_context=True, timeout=120)1464self.wait_text("Quicktune: %s P done" % axis, check_context=True, timeout=120)1465self.wait_text("Quicktune: %s done" % axis, check_context=True, timeout=120)14661467new_values = self.get_parameters(soften_params)1468for p in original_values.keys():1469threshold = 0.8 * original_values[p]1470self.progress("tuned param %s %.4f need %.4f" % (p, new_values[p], threshold))1471if new_values[p] < threshold:1472raise NotAchievedException(1473"parameter %s %.4f not increased over %.4f" %1474(p, new_values[p], threshold))14751476self.progress("ensure we are not overtuned")1477self.set_parameters({1478'SIM_ENGINE_MUL': 0.9,1479'SIM_ENGINE_FAIL': 1 << 0,1480})14811482self.delay_sim_time(5)14831484# and restore it1485self.set_parameter('SIM_ENGINE_MUL', 1)14861487for i in range(5):1488self.wait_heartbeat()14891490if self.statustext_in_collections("ABORTING"):1491raise NotAchievedException("tune has aborted, overtuned")14921493self.progress("using aux fn for save tune")14941495# to test aux function method, use aux fn for save1496self.run_auxfunc(181, 2)1497self.wait_text("Quicktune: saved", check_context=True)1498self.change_mode("QLAND")14991500self.wait_disarmed(timeout=120)1501self.set_parameter("QWIK_ENABLE", 0)1502self.context_pop()1503self.reboot_sitl()15041505def PrecisionLanding(self):1506'''VTOL precision landing'''15071508self.install_applet_script_context("plane_precland.lua")15091510here = self.mav.location()1511target = self.offset_location_ne(here, 20, 0)15121513self.set_parameters({1514"SCR_ENABLE": 1,1515"PLND_ENABLED": 1,1516"PLND_TYPE": 4,1517"SIM_PLD_ENABLE": 1,1518"SIM_PLD_LAT" : target.lat,1519"SIM_PLD_LON" : target.lng,1520"SIM_PLD_HEIGHT" : 0,1521"SIM_PLD_ALT_LMT" : 50,1522"SIM_PLD_DIST_LMT" : 30,1523"RNGFND1_TYPE": 100,1524"RNGFND1_PIN" : 0,1525"RNGFND1_SCALING" : 12.2,1526"RNGFND1_MAX_CM" : 5000,1527"RNGFND_LANDING" : 1,1528})15291530self.reboot_sitl()15311532self.set_parameters({1533"PLND_ALT_CUTOFF" : 5,1534"SIM_SPEEDUP" : 10,1535})15361537self.context_collect('STATUSTEXT')15381539self.scripting_restart()1540self.wait_text("PLND: Loaded", check_context=True)15411542self.wait_ready_to_arm()1543self.change_mode("GUIDED")1544self.arm_vehicle()1545self.takeoff(60, 'GUIDED')1546self.wait_altitude(58, 62, relative=True)1547self.drain_mav()1548self.change_mode("QRTL")15491550self.wait_text("PLND: Target Acquired", check_context=True, timeout=60)15511552self.wait_disarmed(timeout=180)1553loc2 = self.mav.location()1554error = self.get_distance(target, loc2)1555self.progress("Target error %.1fm" % error)1556if error > 2:1557raise NotAchievedException("too far from target %.1fm" % error)15581559def ShipLanding(self):1560'''ship landing test'''1561self.install_applet_script_context("plane_ship_landing.lua")15621563self.set_parameters({1564"SCR_ENABLE": 1,1565"SIM_SHIP_ENABLE": 1,1566"SIM_SHIP_SPEED": 5,1567"SIM_SHIP_DSIZE": 10,1568"FOLL_ENABLE": 1,1569"FOLL_SYSID": 17,1570"FOLL_OFS_TYPE": 1,1571"SIM_TERRAIN" : 0,1572"TERRAIN_ENABLE" : 0,1573})15741575self.load_mission("takeoff100.txt")15761577self.reboot_sitl(check_position=False)15781579self.context_collect('STATUSTEXT')1580self.set_parameters({1581"SHIP_ENABLE" : 1,1582"SIM_SPEEDUP" : 10,1583})15841585self.scripting_restart()1586self.wait_text("ShipLanding: loaded", check_context=True)15871588self.wait_ready_to_arm()1589self.change_mode("AUTO")1590self.arm_vehicle()1591self.wait_altitude(95, 105, relative=True, timeout=90)1592self.drain_mav()15931594self.wait_text("Mission complete, changing mode to RTL", check_context=True, timeout=60)1595self.wait_text("Descending for approach", check_context=True, timeout=60)1596self.wait_text("Reached target altitude", check_context=True, timeout=120)1597self.wait_text("Starting approach", check_context=True, timeout=120)1598self.wait_text("Land complete", check_context=True, timeout=120)15991600self.wait_disarmed(timeout=180)16011602# we confirm successful landing on the ship from our ground speed. The1603# deck is just 10m in size, so we must be within 10m if we are moving1604# with the deck1605self.wait_groundspeed(4.8, 5.2)16061607def RCDisableAirspeedUse(self):1608'''check disabling airspeed using RC switch'''1609self.set_parameter("RC9_OPTION", 106)1610self.delay_sim_time(5)1611self.set_rc(9, 1000)1612self.wait_sensor_state(1613mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,1614True,1615True,1616True)1617self.set_rc(9, 2000)1618self.wait_sensor_state(1619mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,1620True,1621False,1622True)1623self.set_rc(9, 1000)1624self.wait_sensor_state(1625mavutil.mavlink.MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,1626True,1627True,1628True)16291630self.progress("Disabling airspeed sensor")1631self.context_push()1632self.set_rc(9, 2000)1633self.set_parameters({1634"COMPASS_ENABLE": 0,1635"EK2_ENABLE": 0,1636"AHRS_EKF_TYPE": 3,1637"COMPASS_USE": 0,1638"COMPASS_USE2": 0,1639"COMPASS_USE3": 0,1640"ARMING_CHECK": 589818, # from a logfile, disables compass1641})16421643self.reboot_sitl()16441645self.context_collect('STATUSTEXT')1646self.wait_prearm_sys_status_healthy(timeout=120)1647self.change_mode('QLOITER')1648self.arm_vehicle()1649self.set_rc(3, 2000)1650self.wait_altitude(10, 30, relative=True)1651self.change_mode('FBWA')1652self.wait_statustext('Transition done')1653# the vehicle stays in DCM until there's velocity - make sure1654# we did go to EK3 evenutally, 'though:1655self.wait_statustext('EKF3 active', check_context=True)16561657self.disarm_vehicle(force=True)1658self.context_pop()1659self.reboot_sitl()16601661def mission_MAV_CMD_DO_VTOL_TRANSITION(self):1662'''mission item forces transition'''1663wps = self.create_simple_relhome_mission([1664(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),1665(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, 30),1666self.create_MISSION_ITEM_INT(1667mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,1668p1=mavutil.mavlink.MAV_VTOL_STATE_MC1669),1670(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 200, 30),1671self.create_MISSION_ITEM_INT(1672mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION,1673p1=mavutil.mavlink.MAV_VTOL_STATE_FW1674),1675(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 100, 200, 30),1676(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),1677])1678self.check_mission_upload_download(wps)16791680self.change_mode('AUTO')1681self.wait_ready_to_arm()16821683self.arm_vehicle()1684self.wait_current_waypoint(4)1685self.wait_servo_channel_value(5, 1200, comparator=operator.gt)1686self.wait_current_waypoint(6)1687self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)16881689self.fly_home_land_and_disarm()16901691def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self):1692'''mavlink command forces transition during mission'''1693wps = self.create_simple_relhome_mission([1694(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),1695(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),1696(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),1697])1698self.check_mission_upload_download(wps)16991700self.change_mode('AUTO')1701self.wait_ready_to_arm()17021703self.arm_vehicle()1704self.wait_current_waypoint(2)1705self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)17061707for command in self.run_cmd, self.run_cmd_int:1708command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_MC)1709self.wait_servo_channel_value(5, 1200, comparator=operator.gt, timeout=300)1710command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_FW)1711self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90)17121713self.fly_home_land_and_disarm()17141715def TransitionMinThrottle(self):1716'''Ensure that TKOFF_THR_MIN is applied during the forward transition'''1717wps = self.create_simple_relhome_mission([1718(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),1719(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),1720(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),1721])1722self.check_mission_upload_download(wps)1723self.set_parameter('TKOFF_THR_MIN', 80)17241725self.change_mode('AUTO')1726self.wait_ready_to_arm()17271728self.arm_vehicle()1729self.wait_current_waypoint(2)1730# Wait for 5 seconds into the transition.1731self.delay_sim_time(5)1732# Ensure TKOFF_THR_MIN is still respected.1733thr_min = self.get_parameter('TKOFF_THR_MIN')1734self.wait_servo_channel_value(3, 1000+thr_min*10, comparator=operator.eq)17351736self.fly_home_land_and_disarm()17371738def BackTransitionMinThrottle(self):1739'''Ensure min throttle is applied during back transition.'''1740wps = self.create_simple_relhome_mission([1741(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),1742(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30),1743(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),1744])1745self.check_mission_upload_download(wps)1746self.set_parameter('Q_RTL_MODE', 1)17471748trim_pwm = 1000 + 10*self.get_parameter("TRIM_THROTTLE")1749min_pwm = 1000 + 10*self.get_parameter("THR_MIN")17501751self.change_mode('AUTO')1752self.wait_ready_to_arm()17531754self.arm_vehicle()1755self.context_collect('STATUSTEXT')17561757self.wait_statustext("VTOL airbrake", check_context=True, timeout=300)1758self.wait_servo_channel_value(3, trim_pwm, comparator=operator.le, timeout=1)17591760self.wait_statustext("VTOL position1", check_context=True, timeout=10)1761self.wait_servo_channel_value(3, min_pwm+10, comparator=operator.le, timeout=1)17621763self.wait_disarmed(timeout=60)17641765def MAV_CMD_NAV_TAKEOFF(self):1766'''test issuing takeoff command via mavlink'''1767self.change_mode('GUIDED')1768self.wait_ready_to_arm()17691770self.arm_vehicle()1771self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=5)1772self.wait_altitude(4.5, 5.5, minimum_duration=5, relative=True)1773self.change_mode('QLAND')1774self.wait_disarmed()17751776self.start_subtest("Check NAV_TAKEOFF is above current location, not home location")1777self.change_mode('GUIDED')1778self.wait_ready_to_arm()17791780# reset home 20 metres above current location1781current_alt_abs = self.get_altitude(relative=False)17821783loc = self.mav.location()17841785home_z_ofs = 201786self.run_cmd(1787mavutil.mavlink.MAV_CMD_DO_SET_HOME,1788p5=loc.lat,1789p6=loc.lng,1790p7=current_alt_abs + home_z_ofs,1791)17921793self.arm_vehicle()1794takeoff_alt = 51795self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=takeoff_alt)1796self.wait_altitude(1797current_alt_abs + takeoff_alt - 0.5,1798current_alt_abs + takeoff_alt + 0.5,1799minimum_duration=5,1800relative=False,1801)1802self.change_mode('QLAND')1803self.wait_disarmed()18041805self.reboot_sitl() # unlock home position18061807def Q_GUIDED_MODE(self):1808'''test moving in VTOL mode with SET_POSITION_TARGET_GLOBAL_INT'''1809self.set_parameter('Q_GUIDED_MODE', 1)1810self.change_mode('GUIDED')1811self.wait_ready_to_arm()1812self.arm_vehicle()1813self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, p7=15)1814self.wait_altitude(14, 16, relative=True)18151816loc = self.mav.location()1817self.location_offset_ne(loc, 50, 50)18181819# set position target1820self.run_cmd_int(1821mavutil.mavlink.MAV_CMD_DO_REPOSITION,18220,18231, # reposition flags; 1 means "change to guided"18240,18250,1826int(loc.lat * 1e7),1827int(loc.lng * 1e7),182830, # alt1829frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,1830)1831self.wait_location(loc, timeout=120)18321833self.fly_home_land_and_disarm()18341835def DCMClimbRate(self):1836'''Test the climb rate measurement in DCM with and without GPS'''1837self.wait_ready_to_arm()18381839self.change_mode('QHOVER')1840self.arm_vehicle()1841self.set_rc(3, 2000)1842self.wait_altitude(30, 50, relative=True)18431844# Start Descending1845self.set_rc(3, 1000)1846self.wait_climbrate(-5, -0.5, timeout=10)18471848# Switch to DCM1849self.set_parameter('AHRS_EKF_TYPE', 0)1850self.delay_sim_time(5)18511852# Start Climbing1853self.set_rc(3, 2000)1854self.wait_climbrate(0.5, 5, timeout=10)18551856# Kill any GPSs1857self.set_parameters({1858'SIM_GPS1_ENABLE': 0,1859'SIM_GPS2_ENABLE': 0,1860})1861self.delay_sim_time(5)18621863# Start Descending1864self.set_rc(3, 1000)1865self.wait_climbrate(-5, -0.5, timeout=10)18661867# Force disarm1868self.disarm_vehicle(force=True)18691870def RTL_AUTOLAND_1(self):1871'''test behaviour when RTL_AUTOLAND==1'''18721873self.set_parameters({1874"RTL_AUTOLAND": 1,1875})18761877# when RTL is entered and RTL_AUTOLAND is 1 we should fly home1878# then to the landing sequence. This mission puts the landing1879# sequence well to the West of home so if we go directly there1880# we won't come within 200m of home1881wps = self.create_simple_relhome_mission([1882(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),1883# fly North1884(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),1885# add a waypoint 1km North (which we will look for and trigger RTL1886(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),18871888# *exciting* landing sequence is ~1km West and points away from Home.1889self.create_MISSION_ITEM_INT(1890mavutil.mavlink.MAV_CMD_DO_LAND_START,1891),1892(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),1893(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),1894(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),1895(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),1896])1897self.check_mission_upload_download(wps)18981899self.change_mode('AUTO')1900self.wait_ready_to_arm()19011902self.arm_vehicle()1903self.wait_current_waypoint(3) # will be 2km North here1904self.change_mode('RTL')19051906self.wait_distance_to_home(100, 200, timeout=120)1907self.wait_current_waypoint(7)19081909self.fly_home_land_and_disarm()19101911def send_reposition_to_loc(self, loc):1912self.run_cmd_int(1913mavutil.mavlink.MAV_CMD_DO_REPOSITION,19140,19151, # reposition flags; 1 means "change to guided"19160,19170,1918int(loc.lat * 1e7),1919int(loc.lng * 1e7),192020, # alt1921frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,1922)19231924def reposition_to_loc(self, loc, accuracy=100):1925self.send_reposition_to_loc(loc)1926self.wait_location(1927loc,1928accuracy=accuracy,1929minimum_duration=20,1930timeout=120,1931)19321933def AHRSFlyForwardFlag(self):1934'''ensure FlyForward flag is set appropriately'''1935self.set_parameters({1936"LOG_DISARMED": 1,1937"LOG_REPLAY": 1,1938})1939self.reboot_sitl()19401941self.assert_mode_is('FBWA')1942self.delay_sim_time(10)1943self.change_mode('QHOVER')1944self.delay_sim_time(10)19451946self.wait_ready_to_arm()1947self.arm_vehicle()1948self.set_rc(3, 2000)1949self.wait_altitude(20, 50, relative=True)1950self.context_collect('STATUSTEXT')1951self.change_mode('CRUISE')1952self.set_rc(3, 1500)1953self.wait_statustext('Transition started airspeed', check_context=True)1954self.wait_statustext('Transition airspeed reached', check_context=True)1955self.wait_statustext('Transition done', check_context=True)1956self.delay_sim_time(5)1957self.change_mode('QHOVER')1958self.wait_airspeed(0, 5)1959self.delay_sim_time(5)1960mlog_path = self.current_onboard_log_filepath()1961self.fly_home_land_and_disarm(timeout=600)19621963mlog = self.dfreader_for_path(mlog_path)19641965stage_require_fbwa = "require_fbwa"1966stage_wait_qhover = "wait_qhover"1967stage_verify_qhover_ff = "verify_qhover_ff"1968stage_wait_cruise = "wait_cruise"1969stage_cruise_wait_ff = "cruise_wait_ff"1970stage_qhover2 = "qhover2"1971stage_done = "done"1972stage = stage_require_fbwa1973msgs = {}1974seen_flag_set_in_cruise = False1975FF_BIT_MASK = (1 << 2)1976while stage != stage_done:1977m = mlog.recv_match()1978if m is None:1979raise NotAchievedException(f"Stuck in stage {stage}")1980m_type = m.get_type()1981msgs[m_type] = m19821983if stage == stage_require_fbwa:1984if m_type == 'MODE':1985if m.ModeNum == self.get_mode_from_mode_mapping('MANUAL'):1986# manual to start with1987continue1988fbwa_num = self.get_mode_from_mode_mapping('FBWA')1989print(f"{m.ModeNum=} {fbwa_num=}")1990if m.ModeNum != fbwa_num:1991raise ValueError(f"wanted mode={fbwa_num} got={m.ModeNum}")1992continue1993if m_type == 'RFRN':1994if not m.Flags & FF_BIT_MASK:1995raise ValueError("Expected FF to be set in FBWA")1996stage = stage_wait_qhover1997continue1998continue19992000if stage == stage_wait_qhover:2001if m_type == 'MODE':2002qhover_num = self.get_mode_from_mode_mapping('QHOVER')2003print(f"want={qhover_num} got={m.ModeNum}")2004if m.ModeNum == qhover_num:2005stage = stage_verify_qhover_ff2006continue2007continue2008continue20092010if stage == stage_verify_qhover_ff:2011if m_type == 'RFRN':2012if m.Flags & FF_BIT_MASK:2013raise ValueError("Expected FF to be unset in QHOVER")2014stage = stage_wait_cruise2015continue2016continue20172018if stage == stage_wait_cruise:2019if m_type == 'MODE':2020want_num = self.get_mode_from_mode_mapping('CRUISE')2021if m.ModeNum == want_num:2022stage = stage_cruise_wait_ff2023cruise_wait_ff_start = msgs['ATT'].TimeUS*1e-62024continue2025continue2026continue20272028if stage == stage_cruise_wait_ff:2029if m_type == 'MODE':2030want_num = self.get_mode_from_mode_mapping('CRUISE')2031if want_num != m.ModeNum:2032if not seen_flag_set_in_cruise:2033raise ValueError("Never saw FF get set")2034if m.ModeNum == self.get_mode_from_mode_mapping('QHOVER'):2035stage = stage_qhover22036continue2037continue2038if m_type == 'RFRN':2039flag_set = m.Flags & FF_BIT_MASK2040now = msgs['ATT'].TimeUS*1e-62041delta_t = now - cruise_wait_ff_start2042if delta_t < 8:2043if flag_set:2044raise ValueError("Should not see bit set")2045if delta_t > 10:2046if not flag_set and not seen_flag_set_in_cruise:2047raise ValueError("Should see bit set")2048seen_flag_set_in_cruise = True2049continue2050continue20512052if stage == stage_qhover2:2053'''bit should stay low for qhover 2'''2054if m_type == 'RFRN':2055flag_set = m.Flags & FF_BIT_MASK2056if flag_set:2057raise ValueError("ff should be low in qhover")2058continue2059if m_type == 'MODE':2060if m.ModeNum != self.get_mode_from_mode_mapping('QHOVER'):2061stage = stage_done2062continue2063continue2064continue20652066raise NotAchievedException("Bad stage")20672068def RTL_AUTOLAND_1_FROM_GUIDED(self):2069'''test behaviour when RTL_AUTOLAND==1 and entering from guided'''20702071self.set_parameters({2072"RTL_AUTOLAND": 1,2073})20742075# when RTL is entered and RTL_AUTOLAND is 1 we should fly home2076# then to the landing sequence. This mission puts the landing2077# sequence well to the West of home so if we go directly there2078# we won't come within 200m of home2079wps = self.create_simple_relhome_mission([2080(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30),2081# fly North2082(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30),2083# add a waypoint 1km North (which we will look for and trigger RTL2084(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30),20852086# *exciting* landing sequence is ~1km West and points away from Home.2087self.create_MISSION_ITEM_INT(2088mavutil.mavlink.MAV_CMD_DO_LAND_START,2089),2090(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30),2091(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15),2092(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5),2093(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0),2094])2095self.check_mission_upload_download(wps)2096self.set_current_waypoint(0, check_afterwards=False)20972098self.change_mode('AUTO')2099self.wait_ready_to_arm()21002101here = self.mav.location()2102guided_loc = self.offset_location_ne(here, 500, -500)21032104self.arm_vehicle()2105self.wait_current_waypoint(3) # will be 2km North here2106self.reposition_to_loc(guided_loc)2107self.send_cmd_do_set_mode('RTL')21082109self.wait_distance_to_home(100, 200, timeout=120)2110self.wait_current_waypoint(7)21112112self.fly_home_land_and_disarm()21132114def WindEstimateConsistency(self):2115'''test that DCM and EKF3 roughly agree on wind speed and direction'''2116self.set_parameters({2117'SIM_WIND_SPD': 10, # metres/second2118'SIM_WIND_DIR': 315, # from the North-West2119})2120self.change_mode('TAKEOFF')2121self.wait_ready_to_arm()2122self.arm_vehicle()2123self.delay_sim_time(180)2124mlog = self.dfreader_for_current_onboard_log()2125self.fly_home_land_and_disarm()21262127self.progress("Inspecting dataflash log")2128match_start_time = None2129dcm = None2130xkf2 = None2131while True:2132m = mlog.recv_match(2133type=['DCM', 'XKF2'],2134blocking=True,2135)2136if m is None:2137raise NotAchievedException("Did not see wind estimates match")21382139m_type = m.get_type()2140if m_type == 'DCM':2141dcm = m2142else:2143xkf2 = m2144if dcm is None or xkf2 is None:2145continue21462147now = m.TimeUS * 1e-621482149matches_east = abs(dcm.VWE-xkf2.VWE) < 1.52150matches_north = abs(dcm.VWN-xkf2.VWN) < 1.521512152matches = matches_east and matches_north21532154if not matches:2155match_start_time = None2156continue21572158if match_start_time is None:2159match_start_time = now2160continue21612162if now - match_start_time > 60:2163self.progress("Wind estimates correlated")2164break21652166def tests(self):2167'''return list of all tests'''21682169ret = super(AutoTestQuadPlane, self).tests()2170ret.extend([2171self.FwdThrInVTOL,2172self.AirMode,2173self.TestMotorMask,2174self.PilotYaw,2175self.ParameterChecks,2176self.QAUTOTUNE,2177self.TestLogDownload,2178self.TestLogDownloadWrap,2179self.EXTENDED_SYS_STATE,2180self.Mission,2181self.Weathervane,2182self.QAssist,2183self.GyroFFT,2184self.Tailsitter,2185self.CopterTailsitter,2186self.ICEngine,2187self.ICEngineMission,2188self.MAV_CMD_DO_ENGINE_CONTROL,2189self.MidAirDisarmDisallowed,2190self.GUIDEDToAUTO,2191self.BootInAUTO,2192self.Ship,2193self.WindEstimateConsistency,2194self.MAV_CMD_NAV_LOITER_TO_ALT,2195self.LoiterAltQLand,2196self.VTOLLandSpiral,2197self.VTOLQuicktune,2198self.VTOLQuicktune_CPP,2199self.PrecisionLanding,2200self.ShipLanding,2201Test(self.MotorTest, kwargs={ # tests motors 4 and 22202"mot1_servo_chan": 8, # quad-x second motor cw from f-r2203"mot4_servo_chan": 6, # quad-x third motor cw from f-r2204"wait_finish_text": False,2205"quadplane": True,2206}),2207self.RCDisableAirspeedUse,2208self.mission_MAV_CMD_DO_VTOL_TRANSITION,2209self.mavlink_MAV_CMD_DO_VTOL_TRANSITION,2210self.TransitionMinThrottle,2211self.BackTransitionMinThrottle,2212self.MAV_CMD_NAV_TAKEOFF,2213self.Q_GUIDED_MODE,2214self.DCMClimbRate,2215self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence2216self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence2217self.AHRSFlyForwardFlag,2218])2219return ret222022212222