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/rover.py
Views: 1798
'''1Drive Rover in SITL23AP_FLAKE8_CLEAN45'''67from __future__ import print_function89import copy10import math11import operator12import os13import sys14import time1516import vehicle_test_suite1718from pysim import util1920from vehicle_test_suite import AutoTestTimeoutException21from vehicle_test_suite import NotAchievedException22from vehicle_test_suite import PreconditionFailedException2324from pymavlink import mavextra25from pymavlink import mavutil2627# get location of scripts28testdir = os.path.dirname(os.path.realpath(__file__))2930SITL_START_LOCATION = mavutil.location(40.071374969556928,31-105.22978898137808,321583.702759,33246)343536class AutoTestRover(vehicle_test_suite.TestSuite):37@staticmethod38def get_not_armable_mode_list():39return ["RTL", "SMART_RTL"]4041@staticmethod42def get_not_disarmed_settable_modes_list():43return ["FOLLOW"]4445@staticmethod46def get_no_position_not_settable_modes_list():47return []4849@staticmethod50def get_position_armable_modes_list():51return ["GUIDED", "LOITER", "STEERING", "AUTO"]5253@staticmethod54def get_normal_armable_modes_list():55return ["ACRO", "HOLD", "MANUAL"]5657def log_name(self):58return "Rover"5960def test_filepath(self):61return os.path.realpath(__file__)6263def set_current_test_name(self, name):64self.current_test_name_directory = "ArduRover_Tests/" + name + "/"6566def sitl_start_location(self):67return SITL_START_LOCATION6869def default_frame(self):70return "rover"7172def default_speedup(self):73return 307475def is_rover(self):76return True7778def get_stick_arming_channel(self):79return int(self.get_parameter("RCMAP_ROLL"))8081##########################################################82# TESTS DRIVE83##########################################################84# Drive a square in manual mode85def DriveSquare(self, side=50):86"""Learn/Drive Square with Ch7 option"""8788self.progress("TEST SQUARE")89self.set_parameters({90"RC7_OPTION": 7,91"RC9_OPTION": 58,92})9394self.change_mode('MANUAL')9596self.wait_ready_to_arm()97self.arm_vehicle()9899self.clear_wp(9)100101# first aim north102self.progress("\nTurn right towards north")103self.reach_heading_manual(10)104# save bottom left corner of box as home AND waypoint105self.progress("Save HOME")106self.save_wp()107108self.progress("Save WP")109self.save_wp()110111# pitch forward to fly north112self.progress("\nGoing north %u meters" % side)113self.reach_distance_manual(side)114# save top left corner of square as waypoint115self.progress("Save WP")116self.save_wp()117118# roll right to fly east119self.progress("\nGoing east %u meters" % side)120self.reach_heading_manual(100)121self.reach_distance_manual(side)122# save top right corner of square as waypoint123self.progress("Save WP")124self.save_wp()125126# pitch back to fly south127self.progress("\nGoing south %u meters" % side)128self.reach_heading_manual(190)129self.reach_distance_manual(side)130# save bottom right corner of square as waypoint131self.progress("Save WP")132self.save_wp()133134# roll left to fly west135self.progress("\nGoing west %u meters" % side)136self.reach_heading_manual(280)137self.reach_distance_manual(side)138# save bottom left corner of square (should be near home) as waypoint139self.progress("Save WP")140self.save_wp()141142self.progress("Checking number of saved waypoints")143mavproxy = self.start_mavproxy()144num_wp = self.save_mission_to_file_using_mavproxy(145mavproxy,146os.path.join(testdir, "ch7_mission.txt"))147self.stop_mavproxy(mavproxy)148expected = 7 # home + 6 toggled in149if num_wp != expected:150raise NotAchievedException("Did not get %u waypoints; got %u" %151(expected, num_wp))152153# TODO: actually drive the mission154155self.clear_wp(9)156157self.disarm_vehicle()158159def drive_left_circuit(self):160"""Drive a left circuit, 50m on a side."""161self.change_mode('MANUAL')162self.set_rc(3, 2000)163164self.progress("Driving left circuit")165# do 4 turns166for i in range(0, 4):167# hard left168self.progress("Starting turn %u" % i)169self.set_rc(1, 1000)170self.wait_heading(270 - (90*i), accuracy=10)171self.set_rc(1, 1500)172self.progress("Starting leg %u" % i)173self.wait_distance(50, accuracy=7)174self.set_rc(3, 1500)175self.progress("Circuit complete")176177# def test_throttle_failsafe(self, home, distance_min=10, side=60,178# timeout=300):179# """Fly east, Failsafe, return, land."""180#181# self.mavproxy.send('switch 6\n') # manual mode182# self.wait_mode('MANUAL')183# self.mavproxy.send("param set FS_ACTION 1\n")184#185# # first aim east186# self.progress("turn east")187# if not self.reach_heading_manual(135):188# return False189#190# # fly east 60 meters191# self.progress("# Going forward %u meters" % side)192# if not self.reach_distance_manual(side):193# return False194#195# # pull throttle low196# self.progress("# Enter Failsafe")197# self.mavproxy.send('rc 3 900\n')198#199# tstart = self.get_sim_time()200# success = False201# while self.get_sim_time() < tstart + timeout and not success:202# m = self.mav.recv_match(type='VFR_HUD', blocking=True)203# pos = self.mav.location()204# home_distance = self.get_distance(home, pos)205# self.progress("Alt: %u HomeDistance: %.0f" %206# (m.alt, home_distance))207# # check if we've reached home208# if home_distance <= distance_min:209# self.progress("RTL Complete")210# success = True211#212# # reduce throttle213# self.mavproxy.send('rc 3 1500\n')214# self.mavproxy.expect('AP: Failsafe ended')215# self.mavproxy.send('switch 2\n') # manual mode216# self.wait_heartbeat()217# self.wait_mode('MANUAL')218#219# if success:220# self.progress("Reached failsafe home OK")221# return True222# else:223# self.progress("Failed to reach Home on failsafe RTL - "224# "timed out after %u seconds" % timeout)225# return False226227def Sprayer(self):228"""Test sprayer functionality."""229rc_ch = 5230pump_ch = 5231spinner_ch = 6232pump_ch_min = 1050233pump_ch_trim = 1520234pump_ch_max = 1950235spinner_ch_min = 975236spinner_ch_trim = 1510237spinner_ch_max = 1975238239self.set_parameters({240"SPRAY_ENABLE": 1,241242"SERVO%u_FUNCTION" % pump_ch: 22,243"SERVO%u_MIN" % pump_ch: pump_ch_min,244"SERVO%u_TRIM" % pump_ch: pump_ch_trim,245"SERVO%u_MAX" % pump_ch: pump_ch_max,246247"SERVO%u_FUNCTION" % spinner_ch: 23,248"SERVO%u_MIN" % spinner_ch: spinner_ch_min,249"SERVO%u_TRIM" % spinner_ch: spinner_ch_trim,250"SERVO%u_MAX" % spinner_ch: spinner_ch_max,251252"SIM_SPR_ENABLE": 1,253"SIM_SPR_PUMP": pump_ch,254"SIM_SPR_SPIN": spinner_ch,255256"RC%u_OPTION" % rc_ch: 15,257"LOG_DISARMED": 1,258})259260self.reboot_sitl()261262self.wait_ready_to_arm()263self.arm_vehicle()264265self.progress("test bootup state - it's zero-output!")266self.wait_servo_channel_value(spinner_ch, 0)267self.wait_servo_channel_value(pump_ch, 0)268269self.progress("Enable sprayer")270self.set_rc(rc_ch, 2000)271272self.progress("Testing zero-speed state")273self.wait_servo_channel_value(spinner_ch, spinner_ch_min)274self.wait_servo_channel_value(pump_ch, pump_ch_min)275276self.progress("Testing turning it off")277self.set_rc(rc_ch, 1000)278self.wait_servo_channel_value(spinner_ch, spinner_ch_min)279self.wait_servo_channel_value(pump_ch, pump_ch_min)280281self.progress("Testing turning it back on")282self.set_rc(rc_ch, 2000)283self.wait_servo_channel_value(spinner_ch, spinner_ch_min)284self.wait_servo_channel_value(pump_ch, pump_ch_min)285286self.progress("Testing speed-ramping")287self.set_rc(3, 1700) # start driving forward288289# this is somewhat empirical...290self.wait_servo_channel_value(pump_ch, 1695, timeout=60)291292self.progress("Turning it off again")293self.set_rc(rc_ch, 1000)294self.wait_servo_channel_value(spinner_ch, spinner_ch_min)295self.wait_servo_channel_value(pump_ch, pump_ch_min)296297self.start_subtest("Sprayer Mission")298self.load_mission("sprayer-mission.txt")299self.change_mode("AUTO")300# self.send_debug_trap()301self.progress("Waiting for sprayer to start")302self.wait_servo_channel_value(pump_ch, 1250, timeout=60, comparator=operator.gt)303self.progress("Waiting for sprayer to stop")304self.wait_servo_channel_value(pump_ch, pump_ch_min, timeout=120)305306self.start_subtest("Checking mavlink commands")307self.change_mode("MANUAL")308self.progress("Starting Sprayer")309self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1)310311self.progress("Testing speed-ramping")312self.set_rc(3, 1700) # start driving forward313self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt)314self.start_subtest("Stopping Sprayer")315self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0)316self.wait_servo_channel_value(pump_ch, pump_ch_min)317self.set_rc(3, 1000) # stop driving forward318319self.progress("Sprayer OK")320self.disarm_vehicle()321322def DriveMaxRCIN(self, timeout=30):323"""Drive rover at max RC inputs"""324self.progress("Testing max RC inputs")325self.change_mode("MANUAL")326327self.wait_ready_to_arm()328self.arm_vehicle()329330self.set_rc(3, 2000)331self.set_rc(1, 1000)332333tstart = self.get_sim_time()334while self.get_sim_time_cached() - tstart < timeout:335m = self.assert_receive_message('VFR_HUD')336self.progress("Current speed: %f" % m.groundspeed)337338self.disarm_vehicle()339340#################################################341# AUTOTEST ALL342#################################################343def drive_mission(self, filename, strict=True):344"""Drive a mission from a file."""345self.progress("Driving mission %s" % filename)346wp_count = self.load_mission(filename, strict=strict)347self.wait_ready_to_arm()348self.arm_vehicle()349self.change_mode('AUTO')350self.wait_waypoint(1, wp_count-1, max_dist=5)351self.wait_statustext("Mission Complete", timeout=600)352self.disarm_vehicle()353self.progress("Mission OK")354355def DriveMission(self):356'''Drive Mission rover1.txt'''357self.drive_mission("rover1.txt", strict=False)358359def GripperMission(self):360'''Test Gripper Mission Items'''361self.load_mission("rover-gripper-mission.txt")362self.change_mode('AUTO')363self.wait_ready_to_arm()364self.arm_vehicle()365self.context_collect('STATUSTEXT')366self.wait_statustext("Gripper Grabbed", timeout=60, check_context=True)367self.wait_statustext("Gripper Released", timeout=60, check_context=True)368self.wait_statustext("Mission Complete", timeout=60, check_context=True)369self.disarm_vehicle()370371def _MAV_CMD_DO_SEND_BANNER(self, run_cmd):372'''Get Banner'''373self.context_push()374self.context_collect('STATUSTEXT')375run_cmd(mavutil.mavlink.MAV_CMD_DO_SEND_BANNER)376self.wait_statustext("ArduRover", timeout=1, check_context=True)377self.context_pop()378379def MAV_CMD_DO_SEND_BANNER(self):380'''test MAV_CMD_DO_SEND_BANNER'''381self._MAV_CMD_DO_SEND_BANNER(self.run_cmd)382self._MAV_CMD_DO_SEND_BANNER(self.run_cmd_int)383384def drive_brake_get_stopping_distance(self, speed):385'''measure our stopping distance'''386387self.context_push()388389# controller tends not to meet cruise speed (max of ~14 when 15390# set), thus *1.2391# at time of writing, the vehicle is only capable of 10m/s/s accel392self.set_parameters({393'CRUISE_SPEED': speed*1.2,394'ATC_ACCEL_MAX': 15,395})396self.change_mode("STEERING")397self.set_rc(3, 2000)398self.wait_groundspeed(15, 100)399initial = self.mav.location()400initial_time = time.time()401while time.time() - initial_time < 2:402# wait for a position update from the autopilot403start = self.mav.location()404if start != initial:405break406self.set_rc(3, 1500)407self.wait_groundspeed(0, 0.2) # why do we not stop?!408initial = self.mav.location()409initial_time = time.time()410while time.time() - initial_time < 2:411# wait for a position update from the autopilot412stop = self.mav.location()413if stop != initial:414break415delta = self.get_distance(start, stop)416417self.context_pop()418419return delta420421def DriveBrake(self):422'''Test braking'''423self.set_parameters({424'CRUISE_SPEED': 15,425'ATC_BRAKE': 0,426})427428self.arm_vehicle()429430distance_without_brakes = self.drive_brake_get_stopping_distance(15)431432# brakes on:433self.set_parameter('ATC_BRAKE', 1)434distance_with_brakes = self.drive_brake_get_stopping_distance(15)435436delta = distance_without_brakes - distance_with_brakes437438self.disarm_vehicle()439440if delta < distance_without_brakes * 0.05: # 5% isn't asking for much441raise NotAchievedException("""442Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)443""" %444(distance_with_brakes,445distance_without_brakes,446delta))447448self.progress(449"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %450(distance_with_brakes, distance_without_brakes, delta))451452def drive_rtl_mission_max_distance_from_home(self):453'''maximum distance allowed from home at end'''454return 6.5455456def DriveRTL(self, timeout=120):457'''Drive an RTL Mission'''458self.wait_ready_to_arm()459self.arm_vehicle()460461self.load_mission("rtl.txt")462self.change_mode("AUTO")463464tstart = self.get_sim_time()465while True:466now = self.get_sim_time_cached()467if now - tstart > timeout:468raise AutoTestTimeoutException("Didn't see wp 3")469m = self.mav.recv_match(type='MISSION_CURRENT',470blocking=True,471timeout=1)472self.progress("MISSION_CURRENT: %s" % str(m))473if m.seq == 3:474break475476self.drain_mav()477478m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=1)479480wp_dist_min = 5481if m.wp_dist < wp_dist_min:482raise PreconditionFailedException(483"Did not start at least %f metres from destination (is=%f)" %484(wp_dist_min, m.wp_dist))485486self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %487(m.wp_dist, wp_dist_min,))488489# wait for mission to complete490self.wait_statustext("Mission Complete", timeout=70)491492# the EKF doesn't pull us down to 0 speed:493self.wait_groundspeed(0, 0.5, timeout=600)494495# current Rover blows straight past the home position and ends496# up ~6m past the home point.497home_distance = self.distance_to_home()498home_distance_min = 5.5499home_distance_max = self.drive_rtl_mission_max_distance_from_home()500if home_distance > home_distance_max:501raise NotAchievedException(502"Did not stop near home (%f metres distant (%f > want > %f))" %503(home_distance, home_distance_min, home_distance_max))504self.disarm_vehicle()505self.progress("RTL Mission OK (%fm)" % home_distance)506507def RTL_SPEED(self, timeout=120):508'''Test RTL_SPEED is honoured'''509510self.upload_simple_relhome_mission([511(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 0, 0),512(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 0),513])514515self.wait_ready_to_arm()516self.arm_vehicle()517518self.change_mode('AUTO')519self.wait_current_waypoint(2, timeout=120)520for speed in 1, 5.5, 1.5, 7.5:521self.set_parameter("RTL_SPEED", speed)522self.change_mode('RTL')523self.wait_groundspeed(speed-0.1, speed+0.1, minimum_duration=10)524self.change_mode('HOLD')525self.do_RTL()526self.disarm_vehicle()527528def AC_Avoidance(self):529'''Test AC Avoidance switch'''530self.load_fence("rover-fence-ac-avoid.txt")531self.set_parameters({532"FENCE_ENABLE": 0,533"PRX1_TYPE": 10,534"RC10_OPTION": 40, # proximity-enable535})536self.reboot_sitl()537# start = self.mav.location()538self.wait_ready_to_arm()539self.arm_vehicle()540# first make sure we can breach the fence:541self.set_rc(10, 1000)542self.change_mode("ACRO")543self.set_rc(3, 1550)544self.wait_distance_to_home(25, 100000, timeout=60)545self.change_mode("RTL")546self.wait_statustext("Reached destination", timeout=60)547# now enable avoidance and make sure we can't:548self.set_rc(10, 2000)549self.change_mode("ACRO")550self.wait_groundspeed(0, 0.7, timeout=60)551# watch for speed zero552self.wait_groundspeed(0, 0.2, timeout=120)553self.disarm_vehicle()554555def ServoRelayEvents(self):556'''Test ServoRelayEvents'''557for method in self.run_cmd, self.run_cmd_int:558self.context_push()559560self.set_parameters({561"RELAY1_FUNCTION": 1, # Enable relay 1 as a standard relay pin562"RELAY2_FUNCTION": 1, # Enable relay 2 as a standard relay pin563})564self.reboot_sitl() # Needed for relay functions to take effect565566method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)567off = self.get_parameter("SIM_PIN_MASK")568method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)569on = self.get_parameter("SIM_PIN_MASK")570if on == off:571raise NotAchievedException(572"Pin mask unchanged after relay cmd")573self.progress("Pin mask changed after relay command")574method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)575576self.set_message_rate_hz("RELAY_STATUS", 10)577578# default configuration for relays in sim have one relay:579self.assert_received_message_field_values('RELAY_STATUS', {580"present": 3,581"on": 0,582})583method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)584self.assert_received_message_field_values('RELAY_STATUS', {585"present": 3,586"on": 1,587})588method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=1)589self.assert_received_message_field_values('RELAY_STATUS', {590"present": 3,591"on": 3,592})593method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)594method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=0)595self.assert_received_message_field_values('RELAY_STATUS', {596"present": 3,597"on": 0,598})599600# add another relay and ensure that it changes the "present field"601self.set_parameters({602"RELAY6_FUNCTION": 1, # Enable relay 6 as a standard relay pin603"RELAY6_PIN": 14, # Set pin number604})605self.reboot_sitl() # Needed for relay function to take effect606self.set_message_rate_hz("RELAY_STATUS", 10) # Need to re-request the message since reboot607608self.assert_received_message_field_values('RELAY_STATUS', {609"present": 35,610"on": 0,611})612method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=1)613self.assert_received_message_field_values('RELAY_STATUS', {614"present": 35,615"on": 32,616})617method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)618self.assert_received_message_field_values('RELAY_STATUS', {619"present": 35,620"on": 33,621})622method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=0)623self.assert_received_message_field_values('RELAY_STATUS', {624"present": 35,625"on": 1,626})627628self.start_subtest("test MAV_CMD_DO_REPEAT_RELAY")629self.context_push()630self.set_parameter("SIM_SPEEDUP", 1)631method(632mavutil.mavlink.MAV_CMD_DO_REPEAT_RELAY,633p1=0, # servo 1634p2=5, # 5 times635p3=0.5, # 1 second between being on636)637for value in 0, 1, 0, 1, 0, 1, 0, 1:638self.wait_message_field_values('RELAY_STATUS', {639"on": value,640})641self.context_pop()642self.delay_sim_time(3)643self.assert_received_message_field_values('RELAY_STATUS', {644"on": 1, # back to initial state645})646self.context_pop()647648self.start_subtest("test MAV_CMD_DO_SET_SERVO")649for value in 1678, 2300, 0:650method(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=13, p2=value)651self.wait_servo_channel_value(13, value)652653self.start_subtest("test MAV_CMD_DO_REPEAT_SERVO")654655self.context_push()656self.set_parameter("SIM_SPEEDUP", 1)657trim = self.get_parameter("SERVO13_TRIM")658value = 2000659method(660mavutil.mavlink.MAV_CMD_DO_REPEAT_SERVO,661p1=12, # servo12662p2=value, # pwm663p3=5, # count664p4=0.5, # cycle time (1 second between high and high)665)666for value in trim, value, trim, value, trim, value, trim, value:667self.wait_servo_channel_value(12, value)668self.context_pop()669670self.set_message_rate_hz("RELAY_STATUS", 0)671672def MAVProxy_SetModeUsingSwitch(self):673"""Set modes via mavproxy switch"""674port = self.sitl_rcin_port(offset=1)675self.customise_SITL_commandline([676"--rc-in-port", str(port),677])678ex = None679try:680self.load_mission(self.arming_test_mission())681self.wait_ready_to_arm()682fnoo = [(1, 'MANUAL'),683(2, 'MANUAL'),684(3, 'RTL'),685(4, 'AUTO'),686(5, 'AUTO'), # non-existant mode, should stay in RTL687(6, 'MANUAL')]688mavproxy = self.start_mavproxy(sitl_rcin_port=port)689for (num, expected) in fnoo:690mavproxy.send('switch %u\n' % num)691self.wait_mode(expected)692self.stop_mavproxy(mavproxy)693except Exception as e:694self.print_exception_caught(e)695ex = e696697# if we don't put things back ourselves then the test cleanup698# doesn't go well as we can't set the RC defaults correctly:699self.customise_SITL_commandline([700])701702if ex is not None:703raise ex704705def MAVProxy_SetModeUsingMode(self):706'''Set modes via mavproxy mode command'''707fnoo = [(1, 'ACRO'),708(3, 'STEERING'),709(4, 'HOLD'),710]711mavproxy = self.start_mavproxy()712for (num, expected) in fnoo:713mavproxy.send('mode manual\n')714self.wait_mode("MANUAL")715mavproxy.send('mode %u\n' % num)716self.wait_mode(expected)717mavproxy.send('mode manual\n')718self.wait_mode("MANUAL")719mavproxy.send('mode %s\n' % expected)720self.wait_mode(expected)721self.stop_mavproxy(mavproxy)722723def ModeSwitch(self):724''''Set modes via modeswitch'''725self.set_parameter("MODE_CH", 8)726self.set_rc(8, 1000)727# mavutil.mavlink.ROVER_MODE_HOLD:728self.set_parameter("MODE6", 4)729# mavutil.mavlink.ROVER_MODE_ACRO730self.set_parameter("MODE5", 1)731self.set_rc(8, 1800) # PWM for mode6732self.wait_mode("HOLD")733self.set_rc(8, 1700) # PWM for mode5734self.wait_mode("ACRO")735self.set_rc(8, 1800) # PWM for mode6736self.wait_mode("HOLD")737self.set_rc(8, 1700) # PWM for mode5738self.wait_mode("ACRO")739740def AuxModeSwitch(self):741'''Set modes via auxswitches'''742# from mavproxy_rc.py743mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815]744self.set_parameter("MODE1", 1) # acro745self.set_rc(8, mapping[1])746self.wait_mode('ACRO')747748self.set_rc(9, 1000)749self.set_rc(10, 1000)750self.set_parameters({751"RC9_OPTION": 53, # steering752"RC10_OPTION": 54, # hold753})754self.set_rc(9, 1900)755self.wait_mode("STEERING")756self.set_rc(10, 1900)757self.wait_mode("HOLD")758759# reset both switches - should go back to ACRO760self.set_rc(9, 1000)761self.set_rc(10, 1000)762self.wait_mode("ACRO")763764self.set_rc(9, 1900)765self.wait_mode("STEERING")766self.set_rc(10, 1900)767self.wait_mode("HOLD")768769self.set_rc(10, 1000) # this re-polls the mode switch770self.wait_mode("ACRO")771self.set_rc(9, 1000)772773def RCOverridesCancel(self):774'''Test RC overrides Cancel'''775self.set_parameter("SYSID_MYGCS", self.mav.source_system)776self.change_mode('MANUAL')777self.wait_ready_to_arm()778self.zero_throttle()779self.arm_vehicle()780# start moving forward a little:781normal_rc_throttle = 1700782throttle_override = 1900783784self.progress("Establishing baseline RC input")785self.set_rc(3, normal_rc_throttle)786self.drain_mav()787tstart = self.get_sim_time()788while True:789if self.get_sim_time_cached() - tstart > 10:790raise AutoTestTimeoutException("Did not get rc change")791m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)792if m.chan3_raw == normal_rc_throttle:793break794795self.progress("Set override with RC_CHANNELS_OVERRIDE")796self.drain_mav()797tstart = self.get_sim_time()798while True:799if self.get_sim_time_cached() - tstart > 10:800raise AutoTestTimeoutException("Did not override")801self.progress("Sending throttle of %u" % (throttle_override,))802self.mav.mav.rc_channels_override_send(8031, # target system8041, # targe component80565535, # chan1_raw80665535, # chan2_raw807throttle_override, # chan3_raw80865535, # chan4_raw80965535, # chan5_raw81065535, # chan6_raw81165535, # chan7_raw81265535) # chan8_raw813814m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)815self.progress("chan3=%f want=%f" % (m.chan3_raw, throttle_override))816if m.chan3_raw == throttle_override:817break818819self.progress("disabling override and making sure we revert to RC input in good time")820self.drain_mav()821tstart = self.get_sim_time()822while True:823if self.get_sim_time_cached() - tstart > 0.5:824raise AutoTestTimeoutException("Did not cancel override")825self.progress("Sending cancel of throttle override")826self.mav.mav.rc_channels_override_send(8271, # target system8281, # targe component82965535, # chan1_raw83065535, # chan2_raw8310, # chan3_raw83265535, # chan4_raw83365535, # chan5_raw83465535, # chan6_raw83565535, # chan7_raw83665535) # chan8_raw837self.do_timesync_roundtrip()838m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)839self.progress("chan3=%f want=%f" % (m.chan3_raw, normal_rc_throttle))840if m.chan3_raw == normal_rc_throttle:841break842self.disarm_vehicle()843844def RCOverrides(self):845'''Test RC overrides'''846self.set_parameter("SYSID_MYGCS", self.mav.source_system)847self.set_parameter("RC12_OPTION", 46)848self.reboot_sitl()849850self.change_mode('MANUAL')851self.wait_ready_to_arm()852self.set_rc(3, 1500) # throttle at zero853self.arm_vehicle()854# start moving forward a little:855normal_rc_throttle = 1700856self.set_rc(3, normal_rc_throttle)857self.wait_groundspeed(5, 100)858859# allow overrides:860self.set_rc(12, 2000)861862# now override to stop:863throttle_override = 1500864865tstart = self.get_sim_time_cached()866while True:867if self.get_sim_time_cached() - tstart > 10:868raise AutoTestTimeoutException("Did not reach speed")869self.progress("Sending throttle of %u" % (throttle_override,))870self.mav.mav.rc_channels_override_send(8711, # target system8721, # targe component87365535, # chan1_raw87465535, # chan2_raw875throttle_override, # chan3_raw87665535, # chan4_raw87765535, # chan5_raw87865535, # chan6_raw87965535, # chan7_raw88065535) # chan8_raw881882m = self.mav.recv_match(type='VFR_HUD', blocking=True)883want_speed = 2.0884self.progress("Speed=%f want=<%f" % (m.groundspeed, want_speed))885if m.groundspeed < want_speed:886break887888# now override to stop - but set the switch on the RC889# transmitter to deny overrides; this should send the890# speed back up to 5 metres/second:891self.set_rc(12, 1000)892893throttle_override = 1500894tstart = self.get_sim_time_cached()895while True:896if self.get_sim_time_cached() - tstart > 10:897raise AutoTestTimeoutException("Did not speed back up")898self.progress("Sending throttle of %u" % (throttle_override,))899self.mav.mav.rc_channels_override_send(9001, # target system9011, # targe component90265535, # chan1_raw90365535, # chan2_raw904throttle_override, # chan3_raw90565535, # chan4_raw90665535, # chan5_raw90765535, # chan6_raw90865535, # chan7_raw90965535) # chan8_raw910911m = self.mav.recv_match(type='VFR_HUD', blocking=True)912want_speed = 5.0913self.progress("Speed=%f want=>%f" % (m.groundspeed, want_speed))914915if m.groundspeed > want_speed:916break917918# re-enable RC overrides919self.set_rc(12, 2000)920921# check we revert to normal RC inputs when gcs overrides cease:922self.progress("Waiting for RC to revert to normal RC input")923self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)924925self.start_subtest("Check override time of zero disables overrides")926old = self.get_parameter("RC_OVERRIDE_TIME")927ch = 2928self.set_rc(ch, 1000)929channels = [65535] * 18930ch_override_value = 1700931channels[ch-1] = ch_override_value932channels[7] = 1234 # that's channel 8!933self.progress("Sending override message %u" % ch_override_value)934self.mav.mav.rc_channels_override_send(9351, # target system9361, # targe component937*channels938)939# long timeout required here as we may have sent a lot of940# things via MAVProxy...941self.wait_rc_channel_value(ch, ch_override_value, timeout=30)942self.set_parameter("RC_OVERRIDE_TIME", 0)943self.wait_rc_channel_value(ch, 1000)944self.set_parameter("RC_OVERRIDE_TIME", old)945self.wait_rc_channel_value(ch, ch_override_value)946947ch_override_value = 1720948channels[ch-1] = ch_override_value949self.progress("Sending override message %u" % ch_override_value)950self.mav.mav.rc_channels_override_send(9511, # target system9521, # targe component953*channels954)955self.wait_rc_channel_value(ch, ch_override_value, timeout=10)956self.set_parameter("RC_OVERRIDE_TIME", 0)957self.wait_rc_channel_value(ch, 1000)958self.set_parameter("RC_OVERRIDE_TIME", old)959960self.progress("Ensuring timeout works")961self.wait_rc_channel_value(ch, 1000, timeout=5)962self.delay_sim_time(10)963964self.set_parameter("RC_OVERRIDE_TIME", 10)965self.progress("Sending override message")966967ch_override_value = 1730968channels[ch-1] = ch_override_value969self.progress("Sending override message %u" % ch_override_value)970self.mav.mav.rc_channels_override_send(9711, # target system9721, # targe component973*channels974)975self.wait_rc_channel_value(ch, ch_override_value, timeout=10)976tstart = self.get_sim_time()977self.progress("Waiting for channel to revert to 1000 in ~10s")978self.wait_rc_channel_value(ch, 1000, timeout=15)979delta = self.get_sim_time() - tstart980if delta > 12:981raise NotAchievedException("Took too long to revert RC channel value (delta=%f)" % delta)982min_delta = 9983if delta < min_delta:984raise NotAchievedException("Didn't take long enough to revert RC channel value (delta=%f want>=%f)" %985(delta, min_delta))986self.progress("Disabling RC override timeout")987self.set_parameter("RC_OVERRIDE_TIME", -1)988ch_override_value = 1740989channels[ch-1] = ch_override_value990self.progress("Sending override message %u" % ch_override_value)991self.mav.mav.rc_channels_override_send(9921, # target system9931, # targe component994*channels995)996self.wait_rc_channel_value(ch, ch_override_value, timeout=10)997tstart = self.get_sim_time()998while True:999# warning: this is get_sim_time() and can slurp messages on you!1000delta = self.get_sim_time() - tstart1001if delta > 20:1002break1003m = self.assert_receive_message('RC_CHANNELS', timeout=1)1004channel_field = "chan%u_raw" % ch1005m_value = getattr(m, channel_field)1006if m_value != ch_override_value:1007raise NotAchievedException("Value reverted after %f seconds when it should not have (got=%u) (want=%u)" % (delta, m_value, ch_override_value)) # noqa1008self.set_parameter("RC_OVERRIDE_TIME", old)10091010self.delay_sim_time(10)10111012self.start_subtest("Checking higher-channel semantics")1013self.context_push()1014self.set_parameter("RC_OVERRIDE_TIME", 30)10151016ch = 111017rc_value = 10101018self.set_rc(ch, rc_value)10191020channels = [65535] * 181021ch_override_value = 12341022channels[ch-1] = ch_override_value1023self.progress("Sending override message ch%u=%u" % (ch, ch_override_value))1024self.mav.mav.rc_channels_override_send(10251, # target system10261, # targe component1027*channels1028)1029self.progress("Wait for override value")1030self.wait_rc_channel_value(ch, ch_override_value, timeout=10)10311032self.progress("Sending return-to-RC-input value")1033channels[ch-1] = 655341034self.mav.mav.rc_channels_override_send(10351, # target system10361, # targe component1037*channels1038)1039self.wait_rc_channel_value(ch, rc_value, timeout=10)10401041channels[ch-1] = ch_override_value1042self.progress("Sending override message ch%u=%u" % (ch, ch_override_value))1043self.mav.mav.rc_channels_override_send(10441, # target system10451, # targe component1046*channels1047)1048self.progress("Wait for override value")1049self.wait_rc_channel_value(ch, ch_override_value, timeout=10)10501051# make we keep the override vaue for at least 10 seconds:1052tstart = self.get_sim_time()1053while True:1054if self.get_sim_time_cached() - tstart > 10:1055break1056# try both ignore values:1057ignore_value = 01058if self.get_sim_time_cached() - tstart > 5:1059ignore_value = 655351060self.progress("Sending ignore value %u" % ignore_value)1061channels[ch-1] = ignore_value1062self.mav.mav.rc_channels_override_send(10631, # target system10641, # targe component1065*channels1066)1067if self.get_rc_channel_value(ch) != ch_override_value:1068raise NotAchievedException("Did not maintain value")10691070self.context_pop()10711072self.end_subtest("Checking higher-channel semantics")10731074self.disarm_vehicle()10751076def MANUAL_CONTROL(self):1077'''Test mavlink MANUAL_CONTROL'''1078self.set_parameters({1079"SYSID_MYGCS": self.mav.source_system,1080"RC12_OPTION": 46, # enable/disable rc overrides1081})1082self.reboot_sitl()10831084self.change_mode("MANUAL")1085self.wait_ready_to_arm()1086self.arm_vehicle()1087self.progress("start moving forward a little")1088normal_rc_throttle = 17001089self.set_rc(3, normal_rc_throttle)1090self.wait_groundspeed(5, 100)10911092self.progress("allow overrides")1093self.set_rc(12, 2000)10941095self.progress("now override to stop")1096throttle_override_normalized = 01097expected_throttle = 0 # in VFR_HUD10981099tstart = self.get_sim_time_cached()1100while True:1101if self.get_sim_time_cached() - tstart > 10:1102raise AutoTestTimeoutException("Did not reach speed")1103self.progress("Sending normalized throttle of %d" % (throttle_override_normalized,))1104self.mav.mav.manual_control_send(11051, # target system110632767, # x (pitch)110732767, # y (roll)1108throttle_override_normalized, # z (thrust)110932767, # r (yaw)11100) # button mask11111112m = self.mav.recv_match(type='VFR_HUD', blocking=True)1113want_speed = 2.01114self.progress("Speed=%f want=<%f throttle=%u want=%u" %1115(m.groundspeed, want_speed, m.throttle, expected_throttle))1116if m.groundspeed < want_speed and m.throttle == expected_throttle:1117break11181119self.progress("now override to stop - but set the switch on the RC transmitter to deny overrides; this should send the speed back up to 5 metres/second") # noqa1120self.set_rc(12, 1000)11211122throttle_override_normalized = 5001123expected_throttle = 36 # in VFR_HUD, corresponding to normal_rc_throttle adjusted for channel min/max11241125tstart = self.get_sim_time_cached()1126while True:1127if self.get_sim_time_cached() - tstart > 10:1128raise AutoTestTimeoutException("Did not stop")1129self.progress("Sending normalized throttle of %u" % (throttle_override_normalized,))1130self.mav.mav.manual_control_send(11311, # target system113232767, # x (pitch)113332767, # y (roll)1134throttle_override_normalized, # z (thrust)113532767, # r (yaw)11360) # button mask11371138m = self.mav.recv_match(type='VFR_HUD', blocking=True)1139want_speed = 5.011401141self.progress("Speed=%f want=>%f throttle=%u want=%u" %1142(m.groundspeed, want_speed, m.throttle, expected_throttle))1143if m.groundspeed > want_speed and m.throttle == expected_throttle:1144break11451146# re-enable RC overrides1147self.set_rc(12, 2000)11481149# check we revert to normal RC inputs when gcs overrides cease:1150self.progress("Waiting for RC to revert to normal RC input")1151self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)11521153self.disarm_vehicle()11541155def CameraMission(self):1156'''Test Camera Mission Items'''1157self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger1158self.reboot_sitl() # needed for CAM1_TYPE to take effect1159self.load_mission("rover-camera-mission.txt")1160self.wait_ready_to_arm()1161self.change_mode("AUTO")1162self.wait_ready_to_arm()1163self.arm_vehicle()1164prev_cf = None1165while True:1166cf = self.mav.recv_match(type='CAMERA_FEEDBACK', blocking=True)1167if prev_cf is None:1168prev_cf = cf1169continue1170dist_travelled = self.get_distance_int(prev_cf, cf)1171prev_cf = cf1172mc = self.mav.messages.get("MISSION_CURRENT", None)1173if mc is None:1174continue1175elif mc.seq == 2:1176expected_distance = 21177elif mc.seq == 4:1178expected_distance = 51179elif mc.seq == 5:1180break1181else:1182continue1183self.progress("Expected distance %f got %f" %1184(expected_distance, dist_travelled))1185error = abs(expected_distance - dist_travelled)1186# Rover moves at ~5m/s; we appear to do something at1187# 5Hz, so we do see over a meter of error!1188max_error = 1.51189if error > max_error:1190raise NotAchievedException("Camera distance error: %f (%f)" %1191(error, max_error))11921193self.disarm_vehicle()11941195def DO_SET_MODE(self):1196'''Set mode via MAV_COMMAND_DO_SET_MODE'''1197self.do_set_mode_via_command_long("HOLD")1198self.do_set_mode_via_command_long("MANUAL")1199self.do_set_mode_via_command_int("HOLD")1200self.do_set_mode_via_command_int("MANUAL")12011202def RoverInitialMode(self):1203'''test INITIAL_MODE parameter works'''1204# from mavproxy_rc.py1205self.wait_ready_to_arm()1206mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815]1207mode_ch = 81208throttle_ch = 31209self.set_parameter('MODE5', 3)1210self.set_rc(mode_ch, mapping[5])1211self.wait_mode('STEERING')1212self.set_rc(mode_ch, mapping[6])1213self.wait_mode('MANUAL')1214self.set_parameter("INITIAL_MODE", 1) # acro1215# stop the vehicle polling the mode switch at boot:1216self.set_parameter('FS_ACTION', 0) # do nothing when radio fails1217self.set_rc(throttle_ch, 900) # RC fail1218self.reboot_sitl()1219self.wait_mode(1)1220self.progress("Make sure we stay in this mode")1221self.delay_sim_time(5)1222self.wait_mode(1)1223# now change modes with a switch:1224self.set_rc(throttle_ch, 1100)1225self.delay_sim_time(3)1226self.set_rc(mode_ch, mapping[5])1227self.wait_mode('STEERING')12281229def MAVProxy_DO_SET_MODE(self):1230'''Set mode using MAVProxy commandline DO_SET_MODE'''1231mavproxy = self.start_mavproxy()1232self.mavproxy_do_set_mode_via_command_long(mavproxy, "HOLD")1233self.mavproxy_do_set_mode_via_command_long(mavproxy, "MANUAL")1234self.stop_mavproxy(mavproxy)12351236def SYSID_ENFORCE(self):1237'''Test enforcement of SYSID_MYGCS'''1238'''Run the same arming code with correct then incorrect SYSID'''12391240if self.mav.source_system != self.mav.mav.srcSystem:1241raise PreconditionFailedException("Expected mav.source_system and mav.srcSystem to match")12421243self.context_push()1244old_srcSystem = self.mav.mav.srcSystem1245ex = None1246try:1247self.set_parameter("SYSID_MYGCS", self.mav.source_system)1248self.set_parameter("SYSID_ENFORCE", 1, add_to_context=False)12491250self.change_mode('MANUAL')12511252self.progress("make sure I can arm ATM")1253self.wait_ready_to_arm()1254self.arm_vehicle(timeout=5)1255self.disarm_vehicle()12561257self.do_timesync_roundtrip()12581259# should not be able to arm from a system id which is not MY_SYSID1260self.progress("Attempting to arm vehicle from bad system-id")1261success = None1262try:1263# temporarily set a different system ID than normal:1264self.mav.mav.srcSystem = 721265self.arm_vehicle(timeout=5)1266self.disarm_vehicle()1267success = False1268except AutoTestTimeoutException:1269success = True1270self.mav.mav.srcSystem = old_srcSystem1271if not success:1272raise NotAchievedException("Managed to arm with SYSID_ENFORCE set")12731274# should be able to arm from the vehicle's own components:1275self.progress("Attempting to arm vehicle from vehicle component")1276comp_arm_exception = None1277try:1278self.mav.mav.srcSystem = 11279self.arm_vehicle(timeout=5)1280self.disarm_vehicle()1281except Exception as e:1282comp_arm_exception = e1283self.mav.mav.srcSystem = old_srcSystem1284if comp_arm_exception is not None:1285raise comp_arm_exception12861287except Exception as e:1288self.print_exception_caught(e)1289ex = e1290self.mav.mav.srcSystem = old_srcSystem1291self.set_parameter("SYSID_ENFORCE", 0, add_to_context=False)1292self.context_pop()1293if ex is not None:1294raise ex12951296def Rally(self):1297'''Test Rally Points'''1298self.load_rally_using_mavproxy("rover-test-rally.txt")1299self.assert_parameter_value('RALLY_TOTAL', 2)13001301self.wait_ready_to_arm()1302self.arm_vehicle()13031304# calculate early to avoid round-trips while vehicle is moving:1305accuracy = self.get_parameter("WP_RADIUS")13061307self.reach_heading_manual(10)1308self.reach_distance_manual(50)13091310self.change_mode("RTL")13111312# location copied in from rover-test-rally.txt:1313loc = mavutil.location(40.071553,1314-105.229401,13151583,13160)13171318self.wait_location(loc, accuracy=accuracy, minimum_duration=10, timeout=45)1319self.disarm_vehicle()13201321def fence_with_bad_frame(self, target_system=1, target_component=1):1322return [1323self.mav.mav.mission_item_int_encode(1324target_system,1325target_component,13260, # seq1327mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,1328mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,13290, # current13300, # autocontinue13310, # p113320, # p213330, # p313340, # p41335int(1.0017 * 1e7), # latitude1336int(1.0017 * 1e7), # longitude133731.0000, # altitude1338mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1339]13401341def fence_with_zero_vertex_count(self, target_system=1, target_component=1):1342return [1343self.mav.mav.mission_item_int_encode(1344target_system,1345target_component,13460, # seq1347mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1348mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,13490, # current13500, # autocontinue13510, # p113520, # p213530, # p313540, # p41355int(1.0017 * 1e7), # latitude1356int(1.0017 * 1e7), # longitude135731.0000, # altitude1358mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1359]13601361def fence_with_wrong_vertex_count(self, target_system=1, target_component=1):1362return [1363self.mav.mav.mission_item_int_encode(1364target_system,1365target_component,13660, # seq1367mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1368mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,13690, # current13700, # autocontinue13712, # p113720, # p213730, # p313740, # p41375int(1.0017 * 1e7), # latitude1376int(1.0017 * 1e7), # longitude137731.0000, # altitude1378mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1379]13801381def fence_with_multiple_return_points(self, target_system=1, target_component=1):1382return [1383self.mav.mav.mission_item_int_encode(1384target_system,1385target_component,13860, # seq1387mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1388mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,13890, # current13900, # autocontinue13910, # p113920, # p213930, # p313940, # p41395int(1.0017 * 1e7), # latitude1396int(1.0017 * 1e7), # longitude139731.0000, # altitude1398mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1399self.mav.mav.mission_item_int_encode(1400target_system,1401target_component,14021, # seq1403mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1404mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,14050, # current14060, # autocontinue14070, # p114080, # p214090, # p314100, # p41411int(1.0017 * 1e7), # latitude1412int(1.0017 * 1e7), # longitude141331.0000, # altitude1414mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1415]14161417def fence_with_invalid_latlon(self, target_system=1, target_component=1):1418return [1419self.mav.mav.mission_item_int_encode(1420target_system,1421target_component,14220, # seq1423mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1424mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,14250, # current14260, # autocontinue14270, # p114280, # p214290, # p314300, # p41431int(100 * 1e7), # bad latitude. bad.1432int(1.0017 * 1e7), # longitude143331.0000, # altitude1434mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1435]14361437def fence_with_multiple_return_points_with_bad_sequence_numbers(self, target_system=1, target_component=1):1438return [1439self.mav.mav.mission_item_int_encode(1440target_system,1441target_component,14420, # seq1443mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1444mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,14450, # current14460, # autocontinue14470, # p114480, # p214490, # p314500, # p41451int(1.0 * 1e7), # latitude1452int(1.0017 * 1e7), # longitude145331.0000, # altitude1454mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1455self.mav.mav.mission_item_int_encode(1456target_system,1457target_component,14580, # seq1459mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1460mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,14610, # current14620, # autocontinue14630, # p114640, # p214650, # p314660, # p41467int(2.0 * 1e7), # latitude1468int(2.0017 * 1e7), # longitude146931.0000, # altitude1470mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1471]14721473def fence_which_exceeds_storage_space(self, target_system=1, target_component=1):1474ret = []1475for i in range(0, 60):1476ret.append(self.mav.mav.mission_item_int_encode(1477target_system,1478target_component,1479i, # seq1480mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1481mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,14820, # current14830, # autocontinue148410, # p114850, # p214860, # p314870, # p41488int(1.0 * 1e7), # latitude1489int(1.0017 * 1e7), # longitude149031.0000, # altitude1491mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1492)1493return ret14941495def fences_which_should_not_upload(self, target_system=1, target_component=1):1496return [1497("Bad Frame", self.fence_with_bad_frame(1498target_system=target_system,1499target_component=target_component)),1500("Zero Vertex Count", self.fence_with_zero_vertex_count(1501target_system=target_system,1502target_component=target_component)),1503("Wrong Vertex Count", self.fence_with_wrong_vertex_count(1504target_system=target_system,1505target_component=target_component)),1506("Multiple return points", self.fence_with_multiple_return_points(1507target_system=target_system,1508target_component=target_component)),1509("Invalid lat/lon", self.fence_with_invalid_latlon(1510target_system=target_system,1511target_component=target_component)),1512("Multiple Return points with bad sequence numbers",1513self.fence_with_multiple_return_points_with_bad_sequence_numbers( # noqa1514target_system=target_system,1515target_component=target_component)),1516("Fence which exceeds storage space",1517self.fence_which_exceeds_storage_space(1518target_system=target_system,1519target_component=target_component)),1520]15211522def fence_with_single_return_point(self, target_system=1, target_component=1):1523return [1524self.mav.mav.mission_item_int_encode(1525target_system,1526target_component,15270, # seq1528mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1529mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,15300, # current15310, # autocontinue15320, # p115330, # p215340, # p315350, # p41536int(1.0017 * 1e7), # latitude1537int(1.0017 * 1e7), # longitude153831.0000, # altitude1539mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1540]15411542def fence_with_single_return_point_and_5_vertex_inclusion(self,1543target_system=1,1544target_component=1):1545return [1546self.mav.mav.mission_item_int_encode(1547target_system,1548target_component,15490, # seq1550mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1551mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,15520, # current15530, # autocontinue15540, # p115550, # p215560, # p315570, # p41558int(1.0017 * 1e7), # latitude1559int(1.0017 * 1e7), # longitude156031.0000, # altitude1561mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1562self.mav.mav.mission_item_int_encode(1563target_system,1564target_component,15651, # seq1566mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1567mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,15680, # current15690, # autocontinue15705, # p115710, # p215720, # p315730, # p41574int(1.0000 * 1e7), # latitude1575int(1.0000 * 1e7), # longitude157631.0000, # altitude1577mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1578self.mav.mav.mission_item_int_encode(1579target_system,1580target_component,15812, # seq1582mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1583mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,15840, # current15850, # autocontinue15865, # p115870, # p215880, # p315890, # p41590int(1.0001 * 1e7), # latitude1591int(1.0000 * 1e7), # longitude159232.0000, # altitude1593mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1594self.mav.mav.mission_item_int_encode(1595target_system,1596target_component,15973, # seq1598mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1599mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,16000, # current16010, # autocontinue16025, # p116030, # p216040, # p316050, # p41606int(1.0001 * 1e7), # latitude1607int(1.0001 * 1e7), # longitude160833.0000, # altitude1609mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1610self.mav.mav.mission_item_int_encode(1611target_system,1612target_component,16134, # seq1614mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1615mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,16160, # current16170, # autocontinue16185, # p116190, # p216200, # p316210, # p41622int(1.0002 * 1e7), # latitude1623int(1.0002 * 1e7), # longitude162433.0000, # altitude1625mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1626self.mav.mav.mission_item_int_encode(1627target_system,1628target_component,16295, # seq1630mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1631mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,16320, # current16330, # autocontinue16345, # p116350, # p216360, # p316370, # p41638int(1.0002 * 1e7), # latitude1639int(1.0003 * 1e7), # longitude164033.0000, # altitude1641mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1642]16431644def fence_with_many_exclusion_circles(self, count=50, target_system=1, target_component=1):1645ret = []1646for i in range(0, count):1647lat_deg = 1.0003 + count/101648lng_deg = 1.0002 + count/101649item = self.mav.mav.mission_item_int_encode(1650target_system,1651target_component,1652i, # seq1653mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1654mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,16550, # current16560, # autocontinue1657count, # p116580, # p216590, # p316600, # p41661int(lat_deg * 1e7), # latitude1662int(lng_deg * 1e7), # longitude166333.0000, # altitude1664mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1665ret.append(item)1666return ret16671668def fence_with_many_exclusion_polyfences(self, target_system=1, target_component=1):1669ret = []1670seq = 01671for fencenum in range(0, 4):1672pointcount = fencenum + 61673for p in range(0, pointcount):1674lat_deg = 1.0003 + p/10 + fencenum/1001675lng_deg = 1.0002 + p/10 + fencenum/1001676item = self.mav.mav.mission_item_int_encode(1677target_system,1678target_component,1679seq, # seq1680mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1681mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,16820, # current16830, # autocontinue1684pointcount, # p116850, # p216860, # p316870, # p41688int(lat_deg * 1e7), # latitude1689int(lng_deg * 1e7), # longitude169033.0000, # altitude1691mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1692ret.append(item)1693seq += 11694return ret16951696def fences_which_should_upload(self, target_system=1, target_component=1):1697return [1698("Single Return Point",1699self.fence_with_single_return_point(1700target_system=target_system,1701target_component=target_component)),1702("Return and 5-vertex-inclusion",1703self.fence_with_single_return_point_and_5_vertex_inclusion(1704target_system=target_system,1705target_component=target_component)),1706("Many exclusion circles",1707self.fence_with_many_exclusion_circles(1708target_system=target_system,1709target_component=target_component)),1710("Many exclusion polyfences",1711self.fence_with_many_exclusion_polyfences(1712target_system=target_system,1713target_component=target_component)),1714("Empty fence", []),1715]17161717def assert_fence_does_not_upload(self, fence, target_system=1, target_component=1):1718self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,1719target_system=target_system,1720target_component=target_component)1721# upload single item using mission item protocol:1722upload_failed = False1723try:1724self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,1725fence)1726except NotAchievedException:1727# TODO: make sure we failed for correct reason1728upload_failed = True1729if not upload_failed:1730raise NotAchievedException("Uploaded fence when should not be possible")1731self.progress("Fence rightfully bounced")17321733def send_fencepoint_expect_statustext(self,1734offset,1735count,1736lat,1737lng,1738statustext_fragment,1739target_system=1,1740target_component=1,1741timeout=10):1742self.mav.mav.fence_point_send(target_system,1743target_component,1744offset,1745count,1746lat,1747lng)17481749tstart = self.get_sim_time_cached()1750while True:1751if self.get_sim_time_cached() - tstart > timeout:1752raise NotAchievedException("Did not get error message back")1753m = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=1)1754self.progress("statustext: %s (want='%s')" %1755(str(m), statustext_fragment))1756if m is None:1757continue1758if statustext_fragment in m.text:1759break17601761def GCSFailsafe(self, side=60, timeout=360):1762"""Test GCS Failsafe"""1763try:1764self.test_gcs_failsafe(side=side, timeout=timeout)1765except Exception as ex:1766self.setGCSfailsafe(0)1767self.set_parameter('FS_ACTION', 0)1768self.disarm_vehicle(force=True)1769self.reboot_sitl()1770raise ex17711772def test_gcs_failsafe(self, side=60, timeout=360):1773self.set_parameter("SYSID_MYGCS", self.mav.source_system)1774self.set_parameter("FS_ACTION", 1)1775self.set_parameter("FS_THR_ENABLE", 0) # disable radio FS as it inhibt GCS one's17761777def go_somewhere():1778self.change_mode("MANUAL")1779self.wait_ready_to_arm()1780self.arm_vehicle()1781self.set_rc(3, 2000)1782self.delay_sim_time(5)1783self.set_rc(3, 1500)1784# Trigger telemetry loss with failsafe disabled. Verify no action taken.1785self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action")1786self.setGCSfailsafe(0)1787go_somewhere()1788self.set_heartbeat_rate(0)1789self.delay_sim_time(5)1790self.wait_mode("MANUAL")1791self.set_heartbeat_rate(self.speedup)1792self.delay_sim_time(5)1793self.wait_mode("MANUAL")1794self.end_subtest("Completed GCS failsafe disabled test")17951796# Trigger telemetry loss with failsafe enabled. Verify1797# failsafe triggers to RTL. Restore telemetry, verify failsafe1798# clears, and change modes.1799# TODO not implemented1800# self.start_subtest("GCS failsafe recovery test: FS_GCS_ENABLE=1")1801# self.setGCSfailsafe(1)1802# self.set_heartbeat_rate(0)1803# self.wait_mode("RTL")1804# self.set_heartbeat_rate(self.speedup)1805# self.wait_statustext("GCS Failsafe Cleared", timeout=60)1806# self.change_mode("MANUAL")1807# self.end_subtest("Completed GCS failsafe recovery test")18081809# Trigger telemetry loss with failsafe enabled. Verify failsafe triggers and RTL completes1810self.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1")1811self.setGCSfailsafe(1)1812self.set_heartbeat_rate(0)1813self.wait_mode("RTL")1814self.wait_statustext("Reached destination", timeout=60)1815self.set_heartbeat_rate(self.speedup)1816self.wait_statustext("GCS Failsafe Cleared", timeout=60)1817self.end_subtest("Completed GCS failsafe RTL")18181819# Trigger telemetry loss with an invalid failsafe value. Verify failsafe triggers and RTL completes1820self.start_subtest("GCS failsafe invalid value with no options test: FS_GCS_ENABLE=99")1821self.setGCSfailsafe(99)1822go_somewhere()1823self.set_heartbeat_rate(0)1824self.wait_mode("RTL")1825self.wait_statustext("Reached destination", timeout=60)1826self.set_heartbeat_rate(self.speedup)1827self.wait_statustext("GCS Failsafe Cleared", timeout=60)1828self.end_subtest("Completed GCS failsafe invalid value")18291830self.start_subtest("Testing continue in auto mission")1831self.disarm_vehicle()1832self.setGCSfailsafe(2)1833self.load_mission("test_arming.txt")1834self.change_mode("AUTO")1835self.delay_sim_time(5)1836self.set_heartbeat_rate(0)1837self.wait_statustext("Failsafe - Continuing Auto Mode", timeout=60)1838self.delay_sim_time(5)1839self.wait_mode("AUTO")1840self.set_heartbeat_rate(self.speedup)1841self.wait_statustext("GCS Failsafe Cleared", timeout=60)18421843self.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1 and FS_GCS_TIMEOUT=10")1844self.setGCSfailsafe(1)1845old_gcs_timeout = self.get_parameter("FS_GCS_TIMEOUT")1846new_gcs_timeout = old_gcs_timeout * 21847self.set_parameter("FS_GCS_TIMEOUT", new_gcs_timeout)1848go_somewhere()1849self.set_heartbeat_rate(0)1850self.delay_sim_time(old_gcs_timeout + (new_gcs_timeout - old_gcs_timeout) / 2)1851self.assert_mode("MANUAL")1852self.wait_mode("RTL")1853self.wait_statustext("Reached destination", timeout=60)1854self.set_heartbeat_rate(self.speedup)1855self.wait_statustext("GCS Failsafe Cleared", timeout=60)1856self.disarm_vehicle()1857self.end_subtest("Completed GCS failsafe RTL")18581859self.setGCSfailsafe(0)1860self.progress("All GCS failsafe tests complete")18611862def test_gcs_fence_centroid(self, target_system=1, target_component=1):1863self.start_subtest("Ensuring if we don't have a centroid it gets calculated")1864items = self.test_gcs_fence_need_centroid(1865target_system=target_system,1866target_component=target_component)1867self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,1868items)1869centroid = self.get_fence_point(0)1870want_lat = 1.00011871want_lng = 1.000051872if abs(centroid.lat - want_lat) > 0.000001:1873raise NotAchievedException("Centroid lat not as expected (want=%f got=%f)" % (want_lat, centroid.lat))1874if abs(centroid.lng - want_lng) > 0.000001:1875raise NotAchievedException("Centroid lng not as expected (want=%f got=%f)" % (want_lng, centroid.lng))18761877def test_gcs_fence_update_fencepoint(self, target_system=1, target_component=1):1878self.start_subtest("Ensuring we can move a fencepoint")1879items = self.test_gcs_fence_boring_triangle(1880target_system=target_system,1881target_component=target_component)1882self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,1883items)1884# downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1885item_seq = 21886item = items[item_seq]1887print("item is (%s)" % str(item))1888self.progress("original x=%d" % item.x)1889item.x += int(0.1 * 1e7)1890self.progress("new x=%d" % item.x)1891self.progress("try to overwrite item %u" % item_seq)1892self.mav.mav.mission_write_partial_list_send(1893target_system,1894target_component,1895item_seq,1896item_seq,1897mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1898self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, item_seq)1899item.pack(self.mav.mav)1900self.mav.mav.send(item)1901self.progress("Answered request for fence point %u" % item_seq)19021903self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1904downloaded_items2 = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)1905if downloaded_items2[item_seq].x != item.x:1906raise NotAchievedException("Item did not update")1907self.check_fence_items_same([items[0], items[1], item, items[3]], downloaded_items2)19081909def test_gcs_fence_boring_triangle(self, target_system=1, target_component=1):1910return copy.copy([1911self.mav.mav.mission_item_int_encode(1912target_system,1913target_component,19140, # seq1915mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1916mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,19170, # current19180, # autocontinue19193, # p119200, # p219210, # p319220, # p41923int(1.0000 * 1e7), # latitude1924int(1.0000 * 1e7), # longitude192531.0000, # altitude1926mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1927self.mav.mav.mission_item_int_encode(1928target_system,1929target_component,19301, # seq1931mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1932mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,19330, # current19340, # autocontinue19353, # p119360, # p219370, # p319380, # p41939int(1.0001 * 1e7), # latitude1940int(1.0000 * 1e7), # longitude194132.0000, # altitude1942mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1943self.mav.mav.mission_item_int_encode(1944target_system,1945target_component,19462, # seq1947mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1948mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,19490, # current19500, # autocontinue19513, # p119520, # p219530, # p319540, # p41955int(1.0001 * 1e7), # latitude1956int(1.0001 * 1e7), # longitude195733.0000, # altitude1958mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1959self.mav.mav.mission_item_int_encode(1960target_system,1961target_component,19623, # seq1963mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1964mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,19650, # current19660, # autocontinue19670, # p119680, # p219690, # p319700, # p41971int(1.00015 * 1e7), # latitude1972int(1.00015 * 1e7), # longitude197333.0000, # altitude1974mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1975])19761977def test_gcs_fence_need_centroid(self, target_system=1, target_component=1):1978return copy.copy([1979self.mav.mav.mission_item_int_encode(1980target_system,1981target_component,19820, # seq1983mavutil.mavlink.MAV_FRAME_GLOBAL_INT,1984mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,19850, # current19860, # autocontinue19874, # p119880, # p219890, # p319900, # p41991int(1.0000 * 1e7), # latitude1992int(1.0000 * 1e7), # longitude199331.0000, # altitude1994mavutil.mavlink.MAV_MISSION_TYPE_FENCE),1995self.mav.mav.mission_item_int_encode(1996target_system,1997target_component,19981, # seq1999mavutil.mavlink.MAV_FRAME_GLOBAL_INT,2000mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,20010, # current20020, # autocontinue20034, # p120040, # p220050, # p320060, # p42007int(1.0002 * 1e7), # latitude2008int(1.0000 * 1e7), # longitude200932.0000, # altitude2010mavutil.mavlink.MAV_MISSION_TYPE_FENCE),2011self.mav.mav.mission_item_int_encode(2012target_system,2013target_component,20142, # seq2015mavutil.mavlink.MAV_FRAME_GLOBAL_INT,2016mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,20170, # current20180, # autocontinue20194, # p120200, # p220210, # p320220, # p42023int(1.0002 * 1e7), # latitude2024int(1.0001 * 1e7), # longitude202533.0000, # altitude2026mavutil.mavlink.MAV_MISSION_TYPE_FENCE),2027self.mav.mav.mission_item_int_encode(2028target_system,2029target_component,20303, # seq2031mavutil.mavlink.MAV_FRAME_GLOBAL_INT,2032mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,20330, # current20340, # autocontinue20354, # p120360, # p220370, # p320380, # p42039int(1.0000 * 1e7), # latitude2040int(1.0001 * 1e7), # longitude204133.0000, # altitude2042mavutil.mavlink.MAV_MISSION_TYPE_FENCE),2043])20442045def click_location_from_item(self, mavproxy, item):2046mavproxy.send("click %f %f\n" % (item.x*1e-7, item.y*1e-7))20472048def test_gcs_fence_via_mavproxy(self, target_system=1, target_component=1):2049self.start_subtest("Fence via MAVProxy")2050if not self.mavproxy_can_do_mision_item_protocols():2051return2052mavproxy = self.start_mavproxy()2053self.start_subsubtest("fence addcircle")2054self.clear_fence_using_mavproxy(mavproxy)2055self.delay_sim_time(1)2056radius = 202057item = self.mav.mav.mission_item_int_encode(2058target_system,2059target_component,20600, # seq2061mavutil.mavlink.MAV_FRAME_GLOBAL_INT,2062mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,20630, # current20640, # autocontinue2065radius, # p120660, # p220670, # p320680, # p42069int(1.0017 * 1e7), # latitude2070int(1.0017 * 1e7), # longitude20710.0000, # altitude2072mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2073print("item is (%s)" % str(item))2074self.click_location_from_item(mavproxy, item)2075mavproxy.send("fence addcircle inc %u\n" % radius)2076self.delay_sim_time(1)2077downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2078print("downloaded items: %s" % str(downloaded_items))2079self.check_fence_items_same([item], downloaded_items)20802081radius_exc = 57.32082item2 = self.mav.mav.mission_item_int_encode(2083target_system,2084target_component,20850, # seq2086mavutil.mavlink.MAV_FRAME_GLOBAL_INT,2087mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,20880, # current20890, # autocontinue2090radius_exc, # p120910, # p220920, # p320930, # p42094int(1.0017 * 1e7), # latitude2095int(1.0017 * 1e7), # longitude20960.0000, # altitude2097mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2098self.click_location_from_item(mavproxy, item2)2099mavproxy.send("fence addcircle exc %f\n" % radius_exc)2100self.delay_sim_time(1)2101downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2102print("downloaded items: %s" % str(downloaded_items))2103self.check_fence_items_same([item, item2], downloaded_items)2104self.end_subsubtest("fence addcircle")21052106self.start_subsubtest("fence addpoly")2107self.clear_fence_using_mavproxy(mavproxy)2108self.delay_sim_time(1)2109pointcount = 72110mavproxy.send("fence addpoly inc 20 %u 37.2\n" % pointcount) # radius, pointcount, rotaiton2111self.delay_sim_time(5)2112downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2113if len(downloaded_items) != pointcount:2114raise NotAchievedException("Did not get expected number of points returned (want=%u got=%u)" %2115(pointcount, len(downloaded_items)))2116self.end_subsubtest("fence addpoly")21172118self.start_subsubtest("fence movepolypoint")2119self.clear_fence_using_mavproxy(mavproxy)2120self.delay_sim_time(1)2121triangle = self.test_gcs_fence_boring_triangle(2122target_system=target_system,2123target_component=target_component)2124self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,2125triangle)2126mavproxy.send("fence list\n")2127self.delay_sim_time(1)2128triangle[2].x += 5002129triangle[2].y += 7002130self.click_location_from_item(mavproxy, triangle[2])2131mavproxy.send("fence movepolypoint 0 2\n")2132self.delay_sim_time(10)2133downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2134self.check_fence_items_same(triangle, downloaded_items)2135self.end_subsubtest("fence movepolypoint")21362137self.start_subsubtest("fence enable and disable")2138mavproxy.send("fence enable\n")2139mavproxy.expect("fence enabled")2140mavproxy.send("fence disable\n")2141mavproxy.expect("fence disabled")2142self.end_subsubtest("fence enable and disable")21432144self.stop_mavproxy(mavproxy)21452146# MANUAL> usage: fence <addcircle|addpoly|changealt|clear|disable|draw|enable|list|load|move|movemulti|movepolypoint|param|remove|save|savecsv|savelocal|show|status|undo|update> # noqa21472148def GCSFence(self):2149'''Upload and download of fence'''2150target_system = 12151target_component = 121522153self.progress("Testing FENCE_POINT protocol")21542155self.start_subtest("FENCE_TOTAL manipulation")2156self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2157self.assert_parameter_value("FENCE_TOTAL", 0)21582159self.set_parameter("FENCE_TOTAL", 5)2160self.assert_parameter_value("FENCE_TOTAL", 5)21612162self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2163self.assert_parameter_value("FENCE_TOTAL", 0)21642165self.progress("sending out-of-range fencepoint")2166self.send_fencepoint_expect_statustext(0,21670,21681.2345,21695.4321,2170"index past total",2171target_system=target_component,2172target_component=target_component)21732174self.progress("sending another out-of-range fencepoint")2175self.send_fencepoint_expect_statustext(0,21761,21771.2345,21785.4321,2179"bad count",2180target_system=target_component,2181target_component=target_component)21822183self.set_parameter("FENCE_TOTAL", 1)2184self.assert_parameter_value("FENCE_TOTAL", 1)21852186self.send_fencepoint_expect_statustext(0,21871,21881.2345,21895.4321,2190"Invalid FENCE_TOTAL",2191target_system=target_component,2192target_component=target_component)21932194self.set_parameter("FENCE_TOTAL", 5)2195self.progress("Checking default points")2196for i in range(5):2197m = self.get_fence_point(i)2198if m.count != 5:2199raise NotAchievedException("Unexpected count in fence point (want=%u got=%u" %2200(5, m.count))2201if m.lat != 0 or m.lng != 0:2202raise NotAchievedException("Unexpected lat/lon in fencepoint")22032204self.progress("Storing a return point")2205self.roundtrip_fencepoint_protocol(0,22065,22071.2345,22085.4321,2209target_system=target_system,2210target_component=target_component)22112212lat = 2.3452213lng = 4.3212214self.roundtrip_fencepoint_protocol(0,22155,2216lat,2217lng,2218target_system=target_system,2219target_component=target_component)22202221if not self.mavproxy_can_do_mision_item_protocols():2222self.progress("MAVProxy too old to do fence point protocols")2223return22242225self.progress("Download with new protocol")2226items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2227if len(items) != 1:2228raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (1, len(items)))2229if items[0].command != mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:2230raise NotAchievedException(2231"Fence return point not of correct type expected (%u) got %u" %2232(items[0].command,2233mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))2234if items[0].frame != mavutil.mavlink.MAV_FRAME_GLOBAL:2235raise NotAchievedException(2236"Unexpected frame want=%s got=%s," %2237(self.string_for_frame(mavutil.mavlink.MAV_FRAME_GLOBAL),2238self.string_for_frame(items[0].frame)))2239got_lat = items[0].x2240want_lat = lat * 1e72241if abs(got_lat - want_lat) > 1:2242raise NotAchievedException("Disagree in lat (got=%f want=%f)" % (got_lat, want_lat))2243if abs(items[0].y - lng * 1e7) > 1:2244raise NotAchievedException("Disagree in lng")2245if items[0].seq != 0:2246raise NotAchievedException("Disagree in offset")2247self.progress("Downloaded with new protocol OK")22482249# upload using mission protocol:2250items = self.test_gcs_fence_boring_triangle(2251target_system=target_system,2252target_component=target_component)2253self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,2254items)22552256self.progress("Download with new protocol")2257downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)2258if len(downloaded_items) != len(items):2259raise NotAchievedException("Did not download expected number of items (wanted=%u got=%u)" %2260(len(items), len(downloaded_items)))2261self.assert_parameter_value("FENCE_TOTAL", len(items) + 1) # +1 for closing2262self.progress("Ensuring fence items match what we sent up")2263self.check_fence_items_same(items, downloaded_items)22642265# now check centroid2266self.progress("Requesting fence return point")2267self.mav.mav.fence_fetch_point_send(target_system,2268target_component,22690)2270m = self.mav.recv_match(type="FENCE_POINT", blocking=True, timeout=1)2271print("m: %s" % str(m))22722273self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,2274target_system=target_system,2275target_component=target_component)2276self.progress("Checking count post-nuke")2277self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,2278target_system=target_system,2279target_component=target_component)2280self.assert_mission_count_on_link(self.mav,22810,2282target_system,2283target_component,2284mavutil.mavlink.MAV_MISSION_TYPE_FENCE)22852286self.start_subtest("Ensuring bad fences get bounced")2287for fence in self.fences_which_should_not_upload(target_system=target_system, target_component=target_component):2288(name, items) = fence2289self.progress("Ensuring (%s) gets bounced" % (name,))2290self.assert_fence_does_not_upload(items)22912292self.start_subtest("Ensuring good fences don't get bounced")2293for fence in self.fences_which_should_upload(target_system=target_system, target_component=target_component):2294(name, items) = fence2295self.progress("Ensuring (%s) gets uploaded" % (name,))2296self.check_fence_upload_download(items)2297self.progress("(%s) uploaded just fine" % (name,))22982299self.test_gcs_fence_update_fencepoint(target_system=target_system,2300target_component=target_component)23012302self.test_gcs_fence_centroid(target_system=target_system,2303target_component=target_component)23042305self.test_gcs_fence_via_mavproxy(target_system=target_system,2306target_component=target_component)23072308# explode the write_type_to_storage method2309# FIXME: test converting invalid fences / minimally valid fences / normal fences2310# FIXME: show that uploading smaller items take up less space2311# FIXME: add test for consecutive breaches within the manual recovery period2312# FIXME: ensure truncation does the right thing by fence_total23132314# FIXME: test vehicle escape from outside inclusion zones to2315# inside inclusion zones (and inside exclusion zones to outside2316# exclusion zones)2317# FIXME: add test that a fence with edges that cross can't be uploaded2318# FIXME: add a test that fences enclose an area (e.g. all the points aren't the same value!2319def Offboard(self, timeout=90):2320'''Test Offboard Control'''2321self.load_mission("rover-guided-mission.txt")2322self.wait_ready_to_arm(require_absolute=True)2323self.arm_vehicle()2324self.change_mode("AUTO")23252326offboard_expected_duration = 10 # see mission file23272328if self.mav.messages.get("SET_POSITION_TARGET_GLOBAL_INT", None):2329raise PreconditionFailedException("Already have SET_POSITION_TARGET_GLOBAL_INT")23302331tstart = self.get_sim_time_cached()2332last_heartbeat_sent = 02333got_ptgi = False2334magic_waypoint_tstart = 02335magic_waypoint_tstop = 02336while True:2337now = self.get_sim_time_cached()2338if now - last_heartbeat_sent > 1:2339last_heartbeat_sent = now2340self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,2341mavutil.mavlink.MAV_AUTOPILOT_INVALID,23420,23430,23440)23452346if now - tstart > timeout:2347raise AutoTestTimeoutException("Didn't complete")2348magic_waypoint = 32349mc = self.mav.recv_match(type=["MISSION_CURRENT", "STATUSTEXT"],2350blocking=False)2351if mc is not None:2352print("%s" % str(mc))2353if mc.get_type() == "STATUSTEXT":2354if "Mission Complete" in mc.text:2355break2356continue2357if mc.seq == magic_waypoint:2358print("At magic waypoint")2359if magic_waypoint_tstart == 0:2360magic_waypoint_tstart = self.get_sim_time_cached()2361ptgi = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)2362if ptgi is not None:2363got_ptgi = True2364elif mc.seq > magic_waypoint:2365if magic_waypoint_tstop == 0:2366magic_waypoint_tstop = self.get_sim_time_cached()23672368self.disarm_vehicle()2369offboard_duration = magic_waypoint_tstop - magic_waypoint_tstart2370if abs(offboard_duration - offboard_expected_duration) > 1:2371raise NotAchievedException("Did not stay in offboard control for correct time (want=%f got=%f)" %2372(offboard_expected_duration, offboard_duration))23732374if not got_ptgi:2375raise NotAchievedException("Did not get ptgi message")2376print("pgti: %s" % str(ptgi))23772378def assert_mission_count_on_link(self, mav, expected_count, target_system, target_component, mission_type):2379self.drain_mav_unparsed(mav=mav, freshen_sim_time=True)2380self.progress("waiting for a message - any message....")2381m = mav.recv_match(blocking=True, timeout=1)2382self.progress("Received (%s)" % str(m))23832384if not mav.mavlink20():2385raise NotAchievedException("Not doing mavlink2")2386mav.mav.mission_request_list_send(target_system,2387target_component,2388mission_type)2389self.assert_receive_mission_count_on_link(mav,2390expected_count,2391target_system,2392target_component,2393mission_type)23942395def assert_receive_mission_count_on_link(self,2396mav,2397expected_count,2398target_system,2399target_component,2400mission_type,2401expected_target_system=None,2402expected_target_component=None,2403timeout=120):2404if expected_target_system is None:2405expected_target_system = mav.mav.srcSystem2406if expected_target_component is None:2407expected_target_component = mav.mav.srcComponent2408self.progress("Waiting for mission count of (%u) from (%u:%u) to (%u:%u)" %2409(expected_count, target_system, target_component, expected_target_system, expected_target_component))24102411tstart = self.get_sim_time_cached()2412while True:2413delta = self.get_sim_time_cached() - tstart2414if delta > timeout:2415raise NotAchievedException("Did not receive MISSION_COUNT on link after %fs" % delta)2416m = mav.recv_match(blocking=True, timeout=1)2417if m is None:2418self.progress("No messages")2419continue2420# self.progress("Received (%s)" % str(m))2421if m.get_type() == "MISSION_ACK":2422if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:2423raise NotAchievedException("Expected MAV_MISSION_ACCEPTED, got (%s)" % m)2424if m.get_type() == "MISSION_COUNT":2425break2426if m.target_system != expected_target_system:2427raise NotAchievedException("Incorrect target system in MISSION_COUNT (want=%u got=%u)" %2428(expected_target_system, m.target_system))2429if m.target_component != expected_target_component:2430raise NotAchievedException("Incorrect target component in MISSION_COUNT")2431if m.mission_type != mission_type:2432raise NotAchievedException("Did not get expected mission type (want=%u got=%u)" % (mission_type, m.mission_type))2433if m.count != expected_count:2434raise NotAchievedException("Bad count received (want=%u got=%u)" %2435(expected_count, m.count))2436self.progress("Asserted mission count (type=%u) is %u after %fs" % (2437(mission_type, m.count, delta)))24382439def get_mission_item_int_on_link(self, item, mav, target_system, target_component, mission_type, delay_fn=None):2440self.drain_mav(mav=mav, unparsed=True)2441mav.mav.mission_request_int_send(target_system,2442target_component,2443item,2444mission_type)2445m = self.assert_receive_message(2446'MISSION_ITEM_INT',2447timeout=60,2448condition='MISSION_ITEM_INT.mission_type==%u' % mission_type,2449delay_fn=delay_fn)2450if m is None:2451raise NotAchievedException("Did not receive MISSION_ITEM_INT")2452if m.mission_type != mission_type:2453raise NotAchievedException("Mission item of incorrect type")2454if m.target_system != mav.mav.srcSystem:2455raise NotAchievedException("Unexpected target system %u want=%u" %2456(m.target_system, mav.mav.srcSystem))2457if m.seq != item:2458raise NotAchievedException(2459"Incorrect sequence number on received item got=%u want=%u" %2460(m.seq, item))2461if m.mission_type != mission_type:2462raise NotAchievedException(2463"Mission type incorrect on received item (want=%u got=%u)" %2464(mission_type, m.mission_type))2465if m.target_component != mav.mav.srcComponent:2466raise NotAchievedException(2467"Unexpected target component %u want=%u" %2468(m.target_component, mav.mav.srcComponent))2469return m24702471def get_mission_item_on_link(self, item, mav, target_system, target_component, mission_type):2472self.drain_mav(mav=mav, unparsed=True)2473mav.mav.mission_request_send(target_system,2474target_component,2475item,2476mission_type)2477m = mav.recv_match(type='MISSION_ITEM',2478blocking=True,2479timeout=60)2480if m is None:2481raise NotAchievedException("Did not receive MISSION_ITEM")2482if m.target_system != mav.mav.srcSystem:2483raise NotAchievedException("Unexpected target system %u want=%u" %2484(m.target_system, mav.mav.srcSystem))2485if m.seq != item:2486raise NotAchievedException("Incorrect sequence number on received item_int got=%u want=%u" %2487(m.seq, item))2488if m.mission_type != mission_type:2489raise NotAchievedException("Mission type incorrect on received item_int (want=%u got=%u)" %2490(mission_type, m.mission_type))2491if m.target_component != mav.mav.srcComponent:2492raise NotAchievedException("Unexpected target component %u want=%u" %2493(m.target_component, mav.mav.srcComponent))2494return m24952496def assert_receive_mission_item_request(self, mission_type, seq):2497self.progress("Expecting request for item %u" % seq)2498m = self.assert_receive_message('MISSION_REQUEST', timeout=1)2499if m.mission_type != mission_type:2500raise NotAchievedException("Incorrect mission type (wanted=%u got=%u)" %2501(mission_type, m.mission_type))2502if m.seq != seq:2503raise NotAchievedException("Unexpected sequence number (want=%u got=%u)" % (seq, m.seq))2504self.progress("Received item request OK")25052506def assert_receive_mission_ack(self, mission_type,2507want_type=mavutil.mavlink.MAV_MISSION_ACCEPTED,2508target_system=None,2509target_component=None,2510mav=None):2511if mav is None:2512mav = self.mav2513if target_system is None:2514target_system = mav.mav.srcSystem2515if target_component is None:2516target_component = mav.mav.srcComponent2517self.progress("Expecting mission ack")2518m = mav.recv_match(type='MISSION_ACK',2519blocking=True,2520timeout=5)2521self.progress("Received ACK (%s)" % str(m))2522if m is None:2523raise NotAchievedException("Expected mission ACK")2524if m.target_system != target_system:2525raise NotAchievedException("ACK not targetted at correct system want=%u got=%u" %2526(target_system, m.target_system))2527if m.target_component != target_component:2528raise NotAchievedException("ACK not targetted at correct component")2529if m.mission_type != mission_type:2530raise NotAchievedException("Unexpected mission type %u want=%u" %2531(m.mission_type, mission_type))2532if m.type != want_type:2533raise NotAchievedException("Expected ack type %u got %u" %2534(want_type, m.type))25352536def assert_filepath_content(self, filepath, want):2537with open(filepath) as f:2538got = f.read()2539if want != got:2540raise NotAchievedException("Did not get expected file content (want=%s) (got=%s)" % (want, got))25412542def mavproxy_can_do_mision_item_protocols(self):2543return False2544if not self.mavproxy_version_gt(1, 8, 69):2545self.progress("MAVProxy is too old; skipping tests")2546return False2547return True25482549def check_rally_items_same(self, want, got, epsilon=None):2550check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']2551return self.check_mission_items_same(check_atts, want, got, epsilon=epsilon)25522553def click_three_in(self, mavproxy, target_system=1, target_component=1):2554mavproxy.send('rally clear\n')2555self.drain_mav()2556# there are race conditions in MAVProxy. Beware.2557mavproxy.send("click 1.0 1.0\n")2558mavproxy.send("rally add\n")2559self.delay_sim_time(1)2560mavproxy.send("click 2.0 2.0\n")2561mavproxy.send("rally add\n")2562self.delay_sim_time(1)2563mavproxy.send("click 3.0 3.0\n")2564mavproxy.send("rally add\n")2565self.delay_sim_time(10)2566self.assert_mission_count_on_link(2567self.mav,25683,2569target_system,2570target_component,2571mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2572)25732574def GCSRally(self, target_system=1, target_component=1):2575'''Upload and download of rally using MAVProxy'''2576self.start_subtest("Testing mavproxy CLI for rally points")2577if not self.mavproxy_can_do_mision_item_protocols():2578return25792580mavproxy = self.start_mavproxy()25812582mavproxy.send('rally clear\n')25832584self.start_subsubtest("rally add")2585mavproxy.send('rally clear\n')2586lat_s = "-5.6789"2587lng_s = "98.2341"2588lat = float(lat_s)2589lng = float(lng_s)2590mavproxy.send('click %s %s\n' % (lat_s, lng_s))2591self.drain_mav()2592mavproxy.send('rally add\n')2593self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2594target_system=255,2595target_component=0)2596self.delay_sim_time(5)2597downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2598if len(downloaded_items) != 1:2599raise NotAchievedException("Unexpected count (got=%u want=1)" %2600(len(downloaded_items), ))2601if (downloaded_items[0].x - int(lat * 1e7)) > 1:2602raise NotAchievedException("Bad rally lat. Want=%d got=%d" %2603(int(lat * 1e7), downloaded_items[0].x))2604if (downloaded_items[0].y - int(lng * 1e7)) > 1:2605raise NotAchievedException("Bad rally lng. Want=%d got=%d" %2606(int(lng * 1e7), downloaded_items[0].y))2607if (downloaded_items[0].z - int(90)) > 1:2608raise NotAchievedException("Bad rally alt. Want=90 got=%d" %2609(downloaded_items[0].y))2610self.end_subsubtest("rally add")26112612self.start_subsubtest("rally list")2613util.pexpect_drain(mavproxy)2614mavproxy.send('rally list\n')2615mavproxy.expect(r"Saved 1 rally items to ([^\s]*)\s")2616filename = mavproxy.match.group(1)2617self.assert_rally_filepath_content(filename, '''QGC WPL 11026180 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 02619''')2620self.end_subsubtest("rally list")26212622self.start_subsubtest("rally save")2623util.pexpect_drain(mavproxy)2624save_tmppath = self.buildlogs_path("rally-testing-tmp.txt")2625mavproxy.send('rally save %s\n' % save_tmppath)2626mavproxy.expect(r"Saved 1 rally items to ([^\s]*)\s")2627filename = mavproxy.match.group(1)2628if filename != save_tmppath:2629raise NotAchievedException("Bad save filepath; want=%s got=%s" % (save_tmppath, filename))2630self.assert_rally_filepath_content(filename, '''QGC WPL 11026310 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 02632''')2633self.end_subsubtest("rally save")26342635self.start_subsubtest("rally savecsv")2636util.pexpect_drain(mavproxy)2637csvpath = self.buildlogs_path("rally-testing-tmp.csv")2638mavproxy.send('rally savecsv %s\n' % csvpath)2639mavproxy.expect('"Seq","Frame"')2640expected_content = '''"Seq","Frame","Cmd","P1","P2","P3","P4","X","Y","Z"2641"0","Rel","NAV_RALLY_POINT","0.0","0.0","0.0","0.0","-5.67890024185","98.2341003418","90.0"2642'''2643if sys.version_info[0] >= 3:2644# greater precision output by default2645expected_content = '''"Seq","Frame","Cmd","P1","P2","P3","P4","X","Y","Z"2646"0","Rel","NAV_RALLY_POINT","0.0","0.0","0.0","0.0","-5.678900241851807","98.23410034179688","90.0"2647'''2648self.assert_filepath_content(csvpath, expected_content)26492650self.end_subsubtest("rally savecsv")26512652self.start_subsubtest("rally load")2653self.drain_mav()2654mavproxy.send('rally clear\n')2655self.assert_mission_count_on_link(self.mav,26560,2657target_system,2658target_component,2659mavutil.mavlink.MAV_MISSION_TYPE_RALLY)26602661# warning: uses file saved from previous test2662self.start_subtest("Check rally load from filepath")2663mavproxy.send('rally load %s\n' % save_tmppath)2664mavproxy.expect(r"Loaded 1 rally items from ([^\s]*)\s")2665mavproxy.expect("Sent all .* rally items") # notional race condition here2666downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2667if len(downloaded_items) != 1:2668raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))2669if abs(int(downloaded_items[0].x) - int(lat * 1e7)) > 3:2670raise NotAchievedException("Expected lat=%d got=%d" %2671(lat * 1e7, downloaded_items[0].x))2672if abs(int(downloaded_items[0].y) - int(lng * 1e7)) > 10:2673raise NotAchievedException("Expected lng=%d got=%d" %2674(lng * 1e7, downloaded_items[0].y))2675self.end_subsubtest("rally load")26762677self.start_subsubtest("rally changealt")2678mavproxy.send('rally clear\n')2679mavproxy.send("click 1.0 1.0\n")2680mavproxy.send("rally add\n")2681mavproxy.send("click 2.0 2.0\n")2682mavproxy.send("rally add\n")2683self.delay_sim_time(10)2684self.assert_mission_count_on_link(2685self.mav,26862,2687target_system,2688target_component,2689mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2690)2691self.drain_mav()2692mavproxy.send("rally changealt 1 17.6\n")2693self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2694target_system=255,2695target_component=0)2696self.delay_sim_time(10)2697mavproxy.send("rally changealt 2 19.1\n")2698self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2699target_system=255,2700target_component=0)2701self.delay_sim_time(10)2702downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2703if len(downloaded_items) != 2:2704raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))2705if abs(int(downloaded_items[0].x) - int(1 * 1e7)) > 3:2706raise NotAchievedException("Expected lat=%d got=%d" % (1 * 1e7, downloaded_items[0].x))2707if abs(int(downloaded_items[0].y) - int(1 * 1e7)) > 10:2708raise NotAchievedException("Expected lng=%d got=%d" % (1 * 1e7, downloaded_items[0].y))2709# at some stage ArduPilot will stop rounding altitude. This2710# will break then.2711if abs(int(downloaded_items[0].z) - int(17.6)) > 0.0001:2712raise NotAchievedException("Expected alt=%f got=%f" % (17.6, downloaded_items[0].z))27132714if abs(int(downloaded_items[1].x) - int(2 * 1e7)) > 3:2715raise NotAchievedException("Expected lat=%d got=%d" % (2 * 1e7, downloaded_items[0].x))2716if abs(int(downloaded_items[1].y) - int(2 * 1e7)) > 10:2717raise NotAchievedException("Expected lng=%d got=%d" % (2 * 1e7, downloaded_items[0].y))2718# at some stage ArduPilot will stop rounding altitude. This2719# will break then.2720if abs(int(downloaded_items[1].z) - int(19.1)) > 0.0001:2721raise NotAchievedException("Expected alt=%f got=%f" % (19.1, downloaded_items[1].z))27222723self.progress("Now change two at once")2724mavproxy.send("rally changealt 1 17.3 2\n")2725self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2726target_system=255,2727target_component=0)2728downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2729if len(downloaded_items) != 2:2730raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))27312732if abs(int(downloaded_items[0].x) - int(1 * 1e7)) > 3:2733raise NotAchievedException("Expected lat=%d got=%d" % (1 * 1e7, downloaded_items[0].x))2734if abs(int(downloaded_items[0].y) - int(1 * 1e7)) > 10:2735raise NotAchievedException("Expected lng=%d got=%d" % (1 * 1e7, downloaded_items[0].y))2736# at some stage ArduPilot will stop rounding altitude. This2737# will break then.2738if abs(int(downloaded_items[0].z) - int(17.3)) > 0.0001:2739raise NotAchievedException("Expected alt=%f got=%f" % (17.3, downloaded_items[0].z))27402741if abs(int(downloaded_items[1].x) - int(2 * 1e7)) > 3:2742raise NotAchievedException("Expected lat=%d got=%d" % (2 * 1e7, downloaded_items[0].x))2743if abs(int(downloaded_items[1].y) - int(2 * 1e7)) > 10:2744raise NotAchievedException("Expected lng=%d got=%d" % (2 * 1e7, downloaded_items[0].y))2745# at some stage ArduPilot will stop rounding altitude. This2746# will break then.2747if abs(int(downloaded_items[1].z) - int(17.3)) > 0.0001:2748raise NotAchievedException("Expected alt=%f got=%f" % (17.3, downloaded_items[0].z))27492750self.end_subsubtest("rally changealt")27512752self.start_subsubtest("rally move")2753mavproxy.send('rally clear\n')2754mavproxy.send("click 1.0 1.0\n")2755mavproxy.send("rally add\n")2756mavproxy.send("click 2.0 2.0\n")2757mavproxy.send("rally add\n")2758self.delay_sim_time(5)2759self.assert_mission_count_on_link(2760self.mav,27612,2762target_system,2763target_component,2764mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2765)2766mavproxy.send("click 3.0 3.0\n")2767mavproxy.send("rally move 2\n")2768self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2769target_system=255,2770target_component=0)2771mavproxy.send("click 4.12345 4.987654\n")2772mavproxy.send("rally move 1\n")2773self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2774target_system=255,2775target_component=0)27762777downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2778if len(downloaded_items) != 2:2779raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))2780if downloaded_items[0].x != 41234500:2781raise NotAchievedException("Bad latitude")2782if downloaded_items[0].y != 49876540:2783raise NotAchievedException("Bad longitude")2784if downloaded_items[0].z != 90:2785raise NotAchievedException("Bad altitude (want=%u got=%u)" %2786(90, downloaded_items[0].z))27872788if downloaded_items[1].x != 30000000:2789raise NotAchievedException("Bad latitude")2790if downloaded_items[1].y != 30000000:2791raise NotAchievedException("Bad longitude")2792if downloaded_items[1].z != 90:2793raise NotAchievedException("Bad altitude (want=%u got=%u)" %2794(90, downloaded_items[1].z))2795self.end_subsubtest("rally move")27962797self.start_subsubtest("rally movemulti")2798self.drain_mav()2799mavproxy.send('rally clear\n')2800self.drain_mav()2801# there are race conditions in MAVProxy. Beware.2802mavproxy.send("click 1.0 1.0\n")2803mavproxy.send("rally add\n")2804mavproxy.send("click 2.0 2.0\n")2805mavproxy.send("rally add\n")2806mavproxy.send("click 3.0 3.0\n")2807mavproxy.send("rally add\n")2808self.delay_sim_time(10)2809self.assert_mission_count_on_link(2810self.mav,28113,2812target_system,2813target_component,2814mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2815)2816click_lat = 2.02817click_lon = 3.02818unmoved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2819if len(unmoved_items) != 3:2820raise NotAchievedException("Unexpected item count")2821mavproxy.send("click %f %f\n" % (click_lat, click_lon))2822mavproxy.send("rally movemulti 2 1 3\n")2823# MAVProxy currently sends three separate items up. That's2824# not great and I don't want to lock that behaviour in here.2825self.delay_sim_time(10)2826expected_moved_items = copy.copy(unmoved_items)2827expected_moved_items[0].x = 1.0 * 1e72828expected_moved_items[0].y = 2.0 * 1e72829expected_moved_items[1].x = 2.0 * 1e72830expected_moved_items[1].y = 3.0 * 1e72831expected_moved_items[2].x = 3.0 * 1e72832expected_moved_items[2].y = 4.0 * 1e72833moved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2834# we're moving an entire degree in latitude; quite an epsilon required...2835self.check_rally_items_same(expected_moved_items, moved_items, epsilon=10000)28362837self.progress("now move back and rotate through 90 degrees")2838mavproxy.send("click %f %f\n" % (2, 2))2839mavproxy.send("rally movemulti 2 1 3 90\n")28402841# MAVProxy currently sends three separate items up. That's2842# not great and I don't want to lock that behaviour in here.2843self.delay_sim_time(10)2844expected_moved_items = copy.copy(unmoved_items)2845expected_moved_items[0].x = 3.0 * 1e72846expected_moved_items[0].y = 1.0 * 1e72847expected_moved_items[1].x = 2.0 * 1e72848expected_moved_items[1].y = 2.0 * 1e72849expected_moved_items[2].x = 1.0 * 1e72850expected_moved_items[2].y = 3.0 * 1e72851moved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2852# we're moving an entire degree in latitude; quite an epsilon required...2853self.check_rally_items_same(expected_moved_items, moved_items, epsilon=12000)2854self.end_subsubtest("rally movemulti")28552856self.start_subsubtest("rally param")2857mavproxy.send("rally param 3 2 5\n")2858mavproxy.expect("Set param 2 for 3 to 5.000000")2859self.end_subsubtest("rally param")28602861self.start_subsubtest("rally remove")2862self.click_three_in(target_system=target_system, target_component=target_component)2863pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2864self.progress("Removing last in list")2865mavproxy.send("rally remove 3\n")2866self.delay_sim_time(10)2867self.assert_mission_count_on_link(2868self.mav,28692,2870target_system,2871target_component,2872mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2873)2874fewer_downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2875if len(fewer_downloaded_items) != 2:2876raise NotAchievedException("Unexpected download list length")2877shorter_items = copy.copy(pure_items)2878shorter_items = shorter_items[0:2]2879self.check_rally_items_same(shorter_items, fewer_downloaded_items)28802881self.progress("Removing first in list")2882mavproxy.send("rally remove 1\n")2883self.delay_sim_time(5)2884self.assert_mission_count_on_link(2885self.mav,28861,2887target_system,2888target_component,2889mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2890)2891fewer_downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2892if len(fewer_downloaded_items) != 1:2893raise NotAchievedException("Unexpected download list length")2894shorter_items = shorter_items[1:]2895self.check_rally_items_same(shorter_items, fewer_downloaded_items)28962897self.progress("Removing remaining item")2898mavproxy.send("rally remove 1\n")2899self.delay_sim_time(5)2900self.assert_mission_count_on_link(2901self.mav,29020,2903target_system,2904target_component,2905mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2906)2907self.end_subsubtest("rally remove")29082909self.start_subsubtest("rally show")2910# what can we test here?2911mavproxy.send("rally show %s\n" % save_tmppath)2912self.end_subsubtest("rally show")29132914# savelocal must be run immediately after show!2915self.start_subsubtest("rally savelocal")2916util.pexpect_drain(mavproxy)2917savelocal_path = self.buildlogs_path("rally-testing-tmp-local.txt")2918mavproxy.send('rally savelocal %s\n' % savelocal_path)2919self.delay_sim_time(5)2920self.assert_rally_filepath_content(savelocal_path, '''QGC WPL 11029210 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 02922''')2923self.end_subsubtest("rally savelocal")29242925self.start_subsubtest("rally status")2926self.click_three_in(target_system=target_system, target_component=target_component)2927mavproxy.send("rally status\n")2928mavproxy.expect("Have 3 of 3 rally items")2929mavproxy.send("rally clear\n")2930mavproxy.send("rally status\n")2931mavproxy.expect("Have 0 of 0 rally items")2932self.end_subsubtest("rally status")29332934self.start_subsubtest("rally undo")2935self.progress("Testing undo-remove")2936self.click_three_in(target_system=target_system, target_component=target_component)2937pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2938self.progress("Removing first in list")2939mavproxy.send("rally remove 1\n")2940self.delay_sim_time(5)2941self.assert_mission_count_on_link(2942self.mav,29432,2944target_system,2945target_component,2946mavutil.mavlink.MAV_MISSION_TYPE_RALLY,2947)2948mavproxy.send("rally undo\n")2949self.delay_sim_time(5)2950undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2951self.check_rally_items_same(pure_items, undone_items)29522953self.progress("Testing undo-move")29542955pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2956mavproxy.send("click 4.12345 4.987654\n")2957mavproxy.send("rally move 1\n")2958# move has already been tested, assume it works...2959self.delay_sim_time(5)2960mavproxy.send("rally undo\n")2961self.delay_sim_time(5)2962undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2963self.check_rally_items_same(pure_items, undone_items)29642965self.end_subsubtest("rally undo")29662967self.start_subsubtest("rally update")2968self.click_three_in(target_system=target_system, target_component=target_component)2969pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2970rally_update_tmpfilepath = self.buildlogs_path("rally-tmp-update.txt")2971mavproxy.send("rally save %s\n" % rally_update_tmpfilepath)2972self.delay_sim_time(5)2973self.progress("Moving waypoint")2974mavproxy.send("click 13.0 13.0\n")2975mavproxy.send("rally move 1\n")2976self.delay_sim_time(5)2977self.progress("Reverting to original")2978mavproxy.send("rally update %s\n" % rally_update_tmpfilepath)2979self.delay_sim_time(5)2980reverted_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2981self.check_rally_items_same(pure_items, reverted_items)29822983self.progress("Making sure specifying a waypoint to be updated works")2984mavproxy.send("click 13.0 13.0\n")2985mavproxy.send("rally move 1\n")2986self.delay_sim_time(5)2987mavproxy.send("click 17.0 17.0\n")2988mavproxy.send("rally move 2\n")2989self.delay_sim_time(5)2990self.progress("Reverting to original item 2")2991mavproxy.send("rally update %s 2\n" % rally_update_tmpfilepath)2992self.delay_sim_time(5)2993reverted_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)2994if reverted_items[0].x != 130000000:2995raise NotAchievedException("Expected item1 x to stay changed (got=%u want=%u)" % (reverted_items[0].x, 130000000))2996if reverted_items[1].x == 170000000:2997raise NotAchievedException("Expected item2 x to revert")29982999self.end_subsubtest("rally update")3000self.delay_sim_time(1)3001if self.get_parameter("RALLY_TOTAL") != 0:3002raise NotAchievedException("Failed to clear rally points")30033004self.stop_mavproxy(mavproxy)30053006# MANUAL> usage: rally <add|alt|changealt|clear|list|load|move|movemulti|param|remove|save|savecsv|savelocal|show|status|undo|update> # noqa30073008def RallyUploadDownload(self, target_system=1, target_component=1):3009'''Upload and download of rally'''3010old_srcSystem = self.mav.mav.srcSystem30113012self.drain_mav()3013try:3014item1_lat = int(2.0000 * 1e7)3015items = [3016self.mav.mav.mission_item_int_encode(3017target_system,3018target_component,30190, # seq3020mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3021mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,30220, # current30230, # autocontinue30240, # p130250, # p230260, # p330270, # p43028int(1.0000 * 1e7), # latitude3029int(1.0000 * 1e7), # longitude303031.0000, # altitude3031mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3032self.mav.mav.mission_item_int_encode(3033target_system,3034target_component,30351, # seq3036mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3037mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,30380, # current30390, # autocontinue30400, # p130410, # p230420, # p330430, # p43044item1_lat, # latitude3045int(2.0000 * 1e7), # longitude304632.0000, # altitude3047mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3048self.mav.mav.mission_item_int_encode(3049target_system,3050target_component,30512, # seq3052mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3053mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,30540, # current30550, # autocontinue30560, # p130570, # p230580, # p330590, # p43060int(3.0000 * 1e7), # latitude3061int(3.0000 * 1e7), # longitude306233.0000, # altitude3063mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3064]3065self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3066items)3067downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3068print("Got items (%s)" % str(items))3069if len(downloaded) != len(items):3070raise NotAchievedException(3071"Did not download correct number of items want=%u got=%u" %3072(len(downloaded), len(items)))30733074rally_total = self.get_parameter("RALLY_TOTAL")3075if rally_total != len(downloaded):3076raise NotAchievedException(3077"Unexpected rally point count: want=%u got=%u" %3078(len(items), rally_total))30793080self.progress("Pruning count by setting parameter (urgh)")3081self.set_parameter("RALLY_TOTAL", 2)3082downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3083if len(downloaded) != 2:3084raise NotAchievedException(3085"Failed to prune rally points by setting parameter. want=%u got=%u" %3086(2, len(downloaded)))30873088self.progress("Uploading a third item using old protocol")3089new_item2_lat = int(6.0 * 1e7)3090self.set_parameter("RALLY_TOTAL", 3)3091self.mav.mav.rally_point_send(target_system,3092target_component,30932, # sequence number30943, # total count3095new_item2_lat,3096int(7.0 * 1e7),309715,30980, # "break" alt?!30990, # "land dir"31000) # flags3101downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3102if len(downloaded) != 3:3103raise NotAchievedException(3104"resetting rally point count didn't change items returned")3105if downloaded[2].x != new_item2_lat:3106raise NotAchievedException(3107"Bad lattitude in downloaded item: want=%u got=%u" %3108(new_item2_lat, downloaded[2].x))31093110self.progress("Grabbing original item 1 using original protocol")3111self.mav.mav.rally_fetch_point_send(target_system,3112target_component,31131)3114m = self.mav.recv_match(type="RALLY_POINT", blocking=True, timeout=1)3115if m.target_system != self.mav.source_system:3116raise NotAchievedException(3117"Bad target_system on received rally point (want=%u got=%u)" %3118(255, m.target_system))3119if m.target_component != self.mav.source_component: # autotest's component ID3120raise NotAchievedException("Bad target_component on received rally point")3121if m.lat != item1_lat:3122raise NotAchievedException("Bad latitude on received rally point")31233124self.start_subtest("Test upload lockout and timeout")3125self.progress("Starting upload from normal sysid")3126self.mav.mav.mission_count_send(target_system,3127target_component,3128len(items),3129mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3130self.drain_mav() # throw away requests for items3131self.mav.mav.srcSystem = 24331323133self.progress("Attempting upload from sysid=%u" %3134(self.mav.mav.srcSystem,))3135self.mav.mav.mission_count_send(target_system,3136target_component,3137len(items),3138mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3139self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3140want_type=mavutil.mavlink.MAV_MISSION_DENIED)31413142self.progress("Attempting download from sysid=%u" %3143(self.mav.mav.srcSystem,))3144self.mav.mav.mission_request_list_send(target_system,3145target_component,3146mavutil.mavlink.MAV_MISSION_TYPE_RALLY)31473148self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3149want_type=mavutil.mavlink.MAV_MISSION_DENIED)31503151# wait for the upload from sysid=1 to time out:3152tstart = self.get_sim_time()3153got_statustext = False3154got_ack = False3155while True:3156if got_statustext and got_ack:3157self.progress("Got both ack and statustext")3158break3159if self.get_sim_time_cached() - tstart > 100:3160raise NotAchievedException("Did not get both ack and statustext")3161m = self.mav.recv_match(type=['STATUSTEXT', 'MISSION_ACK'],3162blocking=True,3163timeout=1)3164if m is None:3165continue3166self.progress("Got (%s)" % str(m))3167if m.get_type() == 'STATUSTEXT':3168if "upload timeout" in m.text:3169got_statustext = True3170self.progress("Received desired statustext")3171continue3172if m.get_type() == 'MISSION_ACK':3173if m.target_system != old_srcSystem:3174raise NotAchievedException("Incorrect sourcesystem")3175if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:3176raise NotAchievedException("Incorrect result")3177if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_RALLY:3178raise NotAchievedException("Incorrect mission_type")3179got_ack = True3180self.progress("Received desired ACK")3181continue3182raise NotAchievedException("Huh?")31833184self.progress("Now trying to upload empty mission after timeout")3185self.mav.mav.mission_count_send(target_system,3186target_component,31870,3188mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3189self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)31903191self.drain_mav()3192self.start_subtest("Check rally upload/download across separate links")3193self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3194items)3195self.progress("ensure a mavlink1 connection can't do anything useful with new item types")3196self.set_parameter("SERIAL2_PROTOCOL", 1)3197self.reboot_sitl()3198mav2 = mavutil.mavlink_connection("tcp:localhost:5763",3199robust_parsing=True,3200source_system=7,3201source_component=7)3202mav2.mav.mission_request_list_send(target_system,3203target_component,3204mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3205# so this looks a bit odd; the other end isn't sending3206# mavlink2 so can't fill in the extension here.3207self.assert_receive_mission_ack(3208mavutil.mavlink.MAV_MISSION_TYPE_MISSION,3209want_type=mavutil.mavlink.MAV_MISSION_UNSUPPORTED,3210mav=mav2,3211)3212# this relies on magic upgrade to serial2:3213self.set_parameter("SERIAL2_PROTOCOL", 2)3214expected_count = 33215self.progress("Assert mission count on new link")3216self.assert_mission_count_on_link(3217mav2,3218expected_count,3219target_system,3220target_component,3221mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3222self.progress("Assert mission count on original link")3223self.assert_mission_count_on_link(3224self.mav,3225expected_count,3226target_system,3227target_component,3228mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3229self.progress("Get first item on new link")32303231def drain_self_mav_fn():3232self.drain_mav(self.mav)3233m2 = self.get_mission_item_int_on_link(32342,3235mav2,3236target_system,3237target_component,3238mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3239delay_fn=drain_self_mav_fn)3240self.progress("Get first item on original link")3241m = self.get_mission_item_int_on_link(32422,3243self.mav,3244target_system,3245target_component,3246mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3247if m2.x != m.x:3248raise NotAchievedException("mission items do not match (%d vs %d)" % (m2.x, m.x))3249self.get_mission_item_on_link(2, self.mav, target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3250# ensure we get nacks for bad mission item requests:3251self.mav.mav.mission_request_send(target_system,3252target_component,325365,3254mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3255self.assert_receive_mission_ack(3256mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3257want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE,3258)3259self.mav.mav.mission_request_int_send(target_system,3260target_component,326165,3262mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3263self.assert_receive_mission_ack(3264mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3265want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE,3266)32673268self.start_subtest("Should enforce items come from correct GCS")3269self.drain_mav(unparsed=True)3270self.mav.mav.mission_count_send(target_system,3271target_component,32721,3273mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3274self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)3275self.progress("Attempting to upload from bad sysid")3276old_sysid = self.mav.mav.srcSystem3277self.mav.mav.srcSystem = 173278items[0].pack(self.mav.mav)3279self.drain_mav(unparsed=True)3280self.mav.mav.send(items[0])3281self.mav.mav.srcSystem = old_sysid3282self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3283want_type=mavutil.mavlink.MAV_MISSION_DENIED,3284target_system=17)3285self.progress("Sending from correct sysid")3286items[0].pack(self.mav.mav)3287self.drain_mav(unparsed=True)3288self.mav.mav.send(items[0])3289self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)32903291self.drain_mav()3292self.drain_all_pexpects()32933294self.start_subtest("Attempt to send item on different link to that which we are sending requests on")3295self.progress("Sending count")3296self.drain_mav(unparsed=True)3297self.mav.mav.mission_count_send(target_system,3298target_component,32992,3300mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3301self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)3302old_mav2_system = mav2.mav.srcSystem3303old_mav2_component = mav2.mav.srcComponent3304mav2.mav.srcSystem = self.mav.mav.srcSystem3305mav2.mav.srcComponent = self.mav.mav.srcComponent3306self.progress("Sending item on second link")3307# note that the routing table in ArduPilot now will say3308# this sysid/compid is on both links which may cause3309# weirdness...3310items[0].pack(mav2.mav)3311self.drain_mav(mav=self.mav, unparsed=True)3312mav2.mav.send(items[0])3313mav2.mav.srcSystem = old_mav2_system3314mav2.mav.srcComponent = old_mav2_component3315# we continue to receive requests on the original link:3316m = self.assert_receive_message('MISSION_REQUEST', timeout=1)3317if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_RALLY:3318raise NotAchievedException("Mission request of incorrect type")3319if m.seq != 1:3320raise NotAchievedException("Unexpected sequence number (expected=%u got=%u)" % (1, m.seq))3321items[1].pack(self.mav.mav)3322self.drain_mav(unparsed=True)3323self.mav.mav.send(items[1])3324self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)33253326self.drain_mav()3327self.drain_all_pexpects()33283329self.start_subtest("Upload mission and rally points at same time")3330self.progress("Sending rally count")3331self.drain_mav(unparsed=True)3332self.mav.mav.mission_count_send(target_system,3333target_component,33343,3335mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3336self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)33373338self.progress("Sending wp count")3339self.mav.mav.mission_count_send(target_system,3340target_component,33413,3342mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3343self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 0)33443345self.progress("Answering request for mission item 0")3346self.drain_mav(mav=self.mav, unparsed=True)3347self.mav.mav.mission_item_int_send(3348target_system,3349target_component,33500, # seq3351mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3352mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,33530, # current33540, # autocontinue33550, # p133560, # p233570, # p333580, # p43359int(1.1000 * 1e7), # latitude3360int(1.2000 * 1e7), # longitude3361321.0000, # altitude3362mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3363self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 1)33643365self.progress("Answering request for rally point 0")3366items[0].pack(self.mav.mav)3367self.drain_mav(unparsed=True)3368self.mav.mav.send(items[0])3369self.progress("Expecting request for rally item 1")3370self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 1)3371self.progress("Answering request for rally point 1")3372items[1].pack(self.mav.mav)3373self.drain_mav(unparsed=True)3374self.mav.mav.send(items[1])3375self.progress("Expecting request for rally item 2")3376self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 2)33773378self.progress("Answering request for rally point 2")3379items[2].pack(self.mav.mav)3380self.drain_mav(unparsed=True)3381self.mav.mav.send(items[2])3382self.progress("Expecting mission ack for rally")3383self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)33843385self.progress("Answering request for waypoints item 1")3386self.drain_mav(unparsed=True)3387self.mav.mav.mission_item_int_send(3388target_system,3389target_component,33901, # seq3391mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3392mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,33930, # current33940, # autocontinue33950, # p133960, # p233970, # p333980, # p43399int(1.1000 * 1e7), # latitude3400int(1.2000 * 1e7), # longitude3401321.0000, # altitude3402mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3403self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 2)34043405self.progress("Answering request for waypoints item 2")3406self.drain_mav(unparsed=True)3407self.mav.mav.mission_item_int_send(3408target_system,3409target_component,34102, # seq3411mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3412mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,34130, # current34140, # autocontinue34150, # p134160, # p234170, # p334180, # p43419int(1.1000 * 1e7), # latitude3420int(1.2000 * 1e7), # longitude3421321.0000, # altitude3422mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3423self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)34243425self.start_subtest("Test write-partial-list")3426self.progress("Clearing rally points using count-send")3427self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3428target_system=target_system,3429target_component=target_component)3430self.progress("Should not be able to set items completely past the waypoint count")3431self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3432items)3433self.drain_mav(unparsed=True)3434self.mav.mav.mission_write_partial_list_send(3435target_system,3436target_component,343717,343820,3439mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3440self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3441want_type=mavutil.mavlink.MAV_MISSION_ERROR)34423443self.progress("Should not be able to set items overlapping the waypoint count")3444self.drain_mav(unparsed=True)3445self.mav.mav.mission_write_partial_list_send(3446target_system,3447target_component,34480,344920,3450mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3451self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3452want_type=mavutil.mavlink.MAV_MISSION_ERROR)34533454self.progress("try to overwrite items 1 and 2")3455self.drain_mav(unparsed=True)3456self.mav.mav.mission_write_partial_list_send(3457target_system,3458target_component,34591,34602,3461mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3462self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 1)3463self.progress("Try shoving up an incorrectly sequenced item")3464self.drain_mav(unparsed=True)3465self.mav.mav.mission_item_int_send(3466target_system,3467target_component,34680, # seq3469mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3470mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,34710, # current34720, # autocontinue34730, # p134740, # p234750, # p334760, # p43477int(1.1000 * 1e7), # latitude3478int(1.2000 * 1e7), # longitude3479321.0000, # altitude3480mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3481self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3482want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE)34833484self.progress("Try shoving up an incorrectly sequenced item (but within band)")3485self.drain_mav(unparsed=True)3486self.mav.mav.mission_item_int_send(3487target_system,3488target_component,34892, # seq3490mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3491mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,34920, # current34930, # autocontinue34940, # p134950, # p234960, # p334970, # p43498int(1.1000 * 1e7), # latitude3499int(1.2000 * 1e7), # longitude3500321.0000, # altitude3501mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3502self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3503want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE)35043505self.progress("Now provide correct item")3506item1_latitude = int(1.2345 * 1e7)3507self.drain_mav(unparsed=True)3508self.mav.mav.mission_item_int_send(3509target_system,3510target_component,35111, # seq3512mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,3513mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,35140, # current35150, # autocontinue35160, # p135170, # p235180, # p335190, # p43520item1_latitude, # latitude3521int(1.2000 * 1e7), # longitude3522321.0000, # altitude3523mavutil.mavlink.MAV_MISSION_TYPE_RALLY),3524self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 2)3525self.progress("Answering request for rally point 2")3526items[2].pack(self.mav.mav)3527self.drain_mav(unparsed=True)3528self.mav.mav.send(items[2])3529self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3530self.progress("TODO: ensure partial mission write was good")35313532self.start_subtest("clear mission types")3533self.assert_mission_count_on_link(3534self.mav,35353,3536target_system,3537target_component,3538mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3539self.assert_mission_count_on_link(3540self.mav,35413,3542target_system,3543target_component,3544mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3545self.drain_mav(unparsed=True)3546self.mav.mav.mission_clear_all_send(target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3547self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3548self.assert_mission_count_on_link(3549self.mav,35500,3551target_system,3552target_component,3553mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3554self.assert_mission_count_on_link(3555self.mav,35563,3557target_system,3558target_component,3559mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3560self.drain_mav(unparsed=True)3561self.mav.mav.mission_clear_all_send(target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3562self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3563self.assert_mission_count_on_link(3564self.mav,35650,3566target_system,3567target_component,3568mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3569self.assert_mission_count_on_link(3570self.mav,35710,3572target_system,3573target_component,3574mavutil.mavlink.MAV_MISSION_TYPE_MISSION)35753576self.start_subtest("try sending out-of-range counts")3577self.drain_mav(unparsed=True)3578self.mav.mav.mission_count_send(target_system,3579target_component,35801,3581230)3582self.assert_receive_mission_ack(230,3583want_type=mavutil.mavlink.MAV_MISSION_UNSUPPORTED)3584self.drain_mav(unparsed=True)3585self.mav.mav.mission_count_send(target_system,3586target_component,358716000,3588mavutil.mavlink.MAV_MISSION_TYPE_RALLY)3589self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,3590want_type=mavutil.mavlink.MAV_MISSION_NO_SPACE)35913592except Exception as e:3593self.progress("Received exception (%s)" % self.get_exception_stacktrace(e))3594self.mav.mav.srcSystem = old_srcSystem3595raise e3596self.reboot_sitl()35973598def ClearMission(self, target_system=1, target_component=1):3599'''check mission clearing'''36003601self.start_subtest("Clear via mission_clear_all message")3602self.upload_simple_relhome_mission([3603(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),3604(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),3605(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),3606(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),3607(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),3608])3609self.set_current_waypoint(3)36103611self.mav.mav.mission_clear_all_send(3612target_system,3613target_component,3614mavutil.mavlink.MAV_MISSION_TYPE_MISSION3615)36163617self.assert_current_waypoint(0)36183619self.drain_mav()36203621self.start_subtest("No clear mission while it is being uploaded by a different node")3622mav2 = mavutil.mavlink_connection("tcp:localhost:5763",3623robust_parsing=True,3624source_system=7,3625source_component=7)3626self.context_push()3627self.context_collect("MISSION_REQUEST")3628mav2.mav.mission_count_send(target_system,3629target_component,363017,3631mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3632ack = self.assert_receive_message('MISSION_REQUEST', check_context=True, mav=mav2)3633self.context_pop()36343635self.context_push()3636self.context_collect("MISSION_ACK")3637self.mav.mav.mission_clear_all_send(3638target_system,3639target_component,3640mavutil.mavlink.MAV_MISSION_TYPE_MISSION3641)3642ack = self.assert_receive_message('MISSION_ACK', check_context=True)3643self.assert_message_field_values(ack, {3644"type": mavutil.mavlink.MAV_MISSION_DENIED,3645})3646self.context_pop()36473648self.progress("Test cancel upload from second connection")3649self.context_push()3650self.context_collect("MISSION_ACK")3651mav2.mav.mission_clear_all_send(3652target_system,3653target_component,3654mavutil.mavlink.MAV_MISSION_TYPE_MISSION3655)3656ack = self.assert_receive_message('MISSION_ACK', mav=mav2, check_context=True)3657self.assert_message_field_values(ack, {3658"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,3659})3660self.context_pop()3661mav2.close()3662del mav236633664def GCSMission(self):3665'''check MAVProxy's waypoint handling of missions'''36663667target_system = 13668target_component = 13669mavproxy = self.start_mavproxy()3670mavproxy.send('wp clear\n')3671self.delay_sim_time(1)3672if self.get_parameter("MIS_TOTAL") != 0:3673raise NotAchievedException("Failed to clear mission")3674m = self.assert_receive_message('MISSION_CURRENT', timeout=5, verbose=True)3675if m.seq != 0:3676raise NotAchievedException("Bad mission current")3677self.load_mission_using_mavproxy(mavproxy, "rover-gripper-mission.txt")3678set_wp = 13679mavproxy.send('wp set %u\n' % set_wp)3680self.wait_current_waypoint(set_wp)36813682self.start_subsubtest("wp changealt")3683downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3684changealt_item = 13685# oldalt = downloaded_items[changealt_item].z3686want_newalt = 37.23687mavproxy.send('wp changealt %u %f\n' % (changealt_item, want_newalt))3688self.delay_sim_time(15)3689downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3690if abs(downloaded_items[changealt_item].z - want_newalt) > 0.0001:3691raise NotAchievedException(3692"changealt didn't (want=%f got=%f)" %3693(want_newalt, downloaded_items[changealt_item].z))3694self.end_subsubtest("wp changealt")36953696self.start_subsubtest("wp sethome")3697new_home_lat = 3.141593698new_home_lng = 2.718283699mavproxy.send('click %f %f\n' % (new_home_lat, new_home_lng))3700mavproxy.send('wp sethome\n')3701self.delay_sim_time(5)3702# any way to close the loop on this one?3703# downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3704# if abs(downloaded_items[0].x - new_home_lat) > 0.0001:3705# raise NotAchievedException("wp sethome didn't work")3706# if abs(downloaded_items[0].y - new_home_lng) > 0.0001:3707# raise NotAchievedException("wp sethome didn't work")3708self.end_subsubtest("wp sethome")37093710self.start_subsubtest("wp slope")3711mavproxy.send('wp slope\n')3712mavproxy.expect("WP3: slope 0.1")3713self.delay_sim_time(5)3714self.end_subsubtest("wp slope")37153716if not self.mavproxy_can_do_mision_item_protocols():3717# adding based on click location yet to be merged into MAVProxy3718return37193720self.start_subsubtest("wp split")3721mavproxy.send("wp clear\n")3722self.delay_sim_time(5)3723mavproxy.send("wp list\n")3724self.delay_sim_time(5)3725items = [3726None,3727self.mav.mav.mission_item_int_encode(3728target_system,3729target_component,37301, # seq3731mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3732mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,37330, # current37340, # autocontinue37350, # p137360, # p237370, # p337380, # p43739int(1.0 * 1e7), # latitude3740int(1.0 * 1e7), # longitude374133.0000, # altitude3742mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3743self.mav.mav.mission_item_int_encode(3744target_system,3745target_component,37462, # seq3747mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3748mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,37490, # current37500, # autocontinue37510, # p137520, # p237530, # p337540, # p43755int(2.0 * 1e7), # latitude3756int(2.0 * 1e7), # longitude375733.0000, # altitude3758mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3759]3760mavproxy.send("click 5 5\n") # space for home position3761mavproxy.send("wp add\n")3762self.delay_sim_time(5)3763self.click_location_from_item(mavproxy, items[1])3764mavproxy.send("wp add\n")3765self.delay_sim_time(5)3766self.click_location_from_item(mavproxy, items[2])3767mavproxy.send("wp add\n")3768self.delay_sim_time(5)3769downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3770self.check_mission_waypoint_items_same(items, downloaded_items)3771mavproxy.send("wp split 2\n")3772self.delay_sim_time(5)3773items_with_split_in = [3774items[0],3775items[1],3776self.mav.mav.mission_item_int_encode(3777target_system,3778target_component,37792, # seq3780mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3781mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,37820, # current37830, # autocontinue37840, # p137850, # p237860, # p337870, # p43788int(1.5 * 1e7), # latitude3789int(1.5 * 1e7), # longitude379033.0000, # altitude3791mavutil.mavlink.MAV_MISSION_TYPE_MISSION),3792items[2],3793]3794downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)3795self.check_mission_waypoint_items_same(items_with_split_in,3796downloaded_items)37973798self.stop_mavproxy(mavproxy)37993800# MANUAL> usage: wp <changealt|clear|draw|editor|list|load|loop|move|movemulti|noflyadd|param|remove|save|savecsv|savelocal|set|sethome|show|slope|split|status|undo|update> # noqa38013802def wait_location_sending_target(self, loc, target_system=1, target_component=1, timeout=60, max_delta=2):3803tstart = self.get_sim_time()3804last_sent = 038053806type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +3807mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +3808mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +3809mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +3810mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +3811mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +3812mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +3813mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)38143815self.change_mode('GUIDED')3816tstart = self.get_sim_time()3817while True:3818now = self.get_sim_time_cached()3819if now - tstart > timeout:3820raise AutoTestTimeoutException("Did not get to location")3821if now - last_sent > 10:3822last_sent = now3823self.mav.mav.set_position_target_global_int_send(38240,3825target_system,3826target_component,3827mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3828type_mask,3829int(loc.lat * 1.0e7),3830int(loc.lng * 1.0e7),38310, # alt38320, # x-ve38330, # y-vel38340, # z-vel38350, # afx38360, # afy38370, # afz38380, # yaw,38390, # yaw-rate3840)3841m = self.mav.recv_match(blocking=True,3842timeout=1)3843if m is None:3844continue3845t = m.get_type()3846if t == "POSITION_TARGET_GLOBAL_INT":3847self.progress("Target: (%s)" % str(m), send_statustext=False)3848elif t == "GLOBAL_POSITION_INT":3849self.progress("Position: (%s)" % str(m), send_statustext=False)3850delta = self.get_distance(3851mavutil.location(m.lat * 1e-7, m.lon * 1e-7, 0, 0),3852loc)3853self.progress("delta: %s" % str(delta), send_statustext=False)3854if delta < max_delta:3855self.progress("Reached destination")38563857def drive_to_location(self, loc, tolerance=1, timeout=30, target_system=1, target_component=1):3858self.assert_mode('GUIDED')38593860type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +3861mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +3862mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +3863mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +3864mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +3865mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +3866mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +3867mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)38683869last_sent = 03870tstart = self.get_sim_time()3871while True:3872now = self.get_sim_time_cached()3873if now - tstart > timeout:3874raise NotAchievedException("Did not get to location")3875if now - last_sent > 10:3876last_sent = now3877self.mav.mav.set_position_target_global_int_send(38780,3879target_system,3880target_component,3881mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3882type_mask,3883int(loc.lat * 1.0e7),3884int(loc.lng * 1.0e7),38850, # alt38860, # x-ve38870, # y-vel38880, # z-vel38890, # afx38900, # afy38910, # afz38920, # yaw,38930, # yaw-rate3894)3895if self.get_distance(self.mav.location(), loc) > tolerance:3896continue3897return38983899def drive_somewhere_breach_boundary_and_rtl(self, loc, target_system=1, target_component=1, timeout=60):3900tstart = self.get_sim_time()3901last_sent = 03902seen_fence_breach = False39033904type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +3905mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +3906mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +3907mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +3908mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +3909mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +3910mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +3911mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)39123913self.change_mode('GUIDED')3914while True:3915now = self.get_sim_time_cached()3916if now - tstart > timeout:3917raise NotAchievedException("Did not breach boundary + RTL")3918if now - last_sent > 10:3919last_sent = now3920self.mav.mav.set_position_target_global_int_send(39210,3922target_system,3923target_component,3924mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3925type_mask,3926int(loc.lat * 1.0e7),3927int(loc.lng * 1.0e7),39280, # alt39290, # x-ve39300, # y-vel39310, # z-vel39320, # afx39330, # afy39340, # afz39350, # yaw,39360, # yaw-rate3937)3938m = self.mav.recv_match(blocking=True,3939timeout=1)3940if m is None:3941continue3942t = m.get_type()3943if t == "POSITION_TARGET_GLOBAL_INT":3944self.progress("Target: (%s)" % str(m))3945elif t == "GLOBAL_POSITION_INT":3946self.progress("Position: (%s)" % str(m))3947elif t == "FENCE_STATUS":3948self.progress("Fence: %s" % str(m))3949if m.breach_status != 0:3950seen_fence_breach = True3951self.progress("Fence breach detected!")3952if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY:3953raise NotAchievedException("Breach of unexpected type")3954if self.mode_is("RTL", cached=True) and seen_fence_breach:3955break3956self.wait_distance_to_home(3, 7, timeout=30)39573958def drive_somewhere_stop_at_boundary(self,3959loc,3960expected_stopping_point,3961expected_distance_epsilon=1.0,3962target_system=1,3963target_component=1,3964timeout=120):3965tstart = self.get_sim_time()3966last_sent = 039673968type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +3969mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +3970mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +3971mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +3972mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +3973mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +3974mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +3975mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)39763977self.change_mode('GUIDED')3978at_stopping_point = False3979while True:3980now = self.get_sim_time_cached()3981if now - tstart > timeout:3982raise NotAchievedException("Did not arrive and stop at boundary")3983if now - last_sent > 10:3984last_sent = now3985self.mav.mav.set_position_target_global_int_send(39860,3987target_system,3988target_component,3989mavutil.mavlink.MAV_FRAME_GLOBAL_INT,3990type_mask,3991int(loc.lat * 1.0e7),3992int(loc.lng * 1.0e7),39930, # alt39940, # x-ve39950, # y-vel39960, # z-vel39970, # afx39980, # afy39990, # afz40000, # yaw,40010, # yaw-rate4002)4003m = self.mav.recv_match(blocking=True,4004timeout=1)4005if m is None:4006continue4007t = m.get_type()4008if t == "POSITION_TARGET_GLOBAL_INT":4009print("Target: (%s)" % str(m))4010elif t == "GLOBAL_POSITION_INT":4011print("Position: (%s)" % str(m))4012delta = self.get_distance(4013mavutil.location(m.lat * 1e-7, m.lon * 1e-7, 0, 0),4014mavutil.location(expected_stopping_point.lat,4015expected_stopping_point.lng,40160,40170))4018print("delta: %s want_delta<%f" % (str(delta), expected_distance_epsilon))4019at_stopping_point = delta < expected_distance_epsilon4020elif t == "VFR_HUD":4021print("groundspeed: %f" % m.groundspeed)4022if at_stopping_point:4023if m.groundspeed < 1:4024self.progress("Seemed to have stopped at stopping point")4025return40264027def assert_fence_breached(self):4028m = self.assert_receive_message('FENCE_STATUS', timeout=10)4029if m.breach_status != 1:4030raise NotAchievedException("Expected to be breached")40314032def wait_fence_not_breached(self, timeout=5):4033tstart = self.get_sim_time()4034while True:4035if self.get_sim_time_cached() - tstart > timeout:4036raise AutoTestTimeoutException("Fence remains breached")4037m = self.mav.recv_match(type='FENCE_STATUS',4038blocking=True,4039timeout=1)4040if m is None:4041self.progress("No FENCE_STATUS received")4042continue4043self.progress("STATUS: %s" % str(m))4044if m.breach_status == 0:4045break40464047def test_poly_fence_noarms(self, target_system=1, target_component=1):4048'''various tests to ensure we can't arm when in breach of a polyfence'''4049self.start_subtest("Ensure PolyFence arming checks work")4050self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4051target_system=target_system,4052target_component=target_component)4053self.set_parameters({4054"FENCE_TYPE": 2, # circle only4055})4056self.delay_sim_time(5) # let breaches clear4057# FIXME: should we allow this?4058self.progress("Ensure we can arm with no poly in place")4059self.change_mode("GUIDED")4060self.wait_ready_to_arm()4061self.arm_vehicle()4062self.disarm_vehicle()4063self.set_parameters({4064"FENCE_TYPE": 6, # polyfence + circle4065})40664067self.test_poly_fence_noarms_exclusion_circle(target_system=target_system,4068target_component=target_component)4069self.test_poly_fence_noarms_inclusion_circle(target_system=target_system,4070target_component=target_component)4071self.test_poly_fence_noarms_exclusion_polyfence(target_system=target_system,4072target_component=target_component)4073self.test_poly_fence_noarms_inclusion_polyfence(target_system=target_system,4074target_component=target_component)40754076def test_poly_fence_noarms_exclusion_circle(self, target_system=1, target_component=1):4077self.start_subtest("Ensure not armable when within an exclusion circle")40784079here = self.mav.location()40804081items = [4082self.mav.mav.mission_item_int_encode(4083target_system,4084target_component,40850, # seq4086mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4087mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,40880, # current40890, # autocontinue40905, # p1 - radius40910, # p240920, # p340930, # p44094int(here.lat * 1e7), # latitude4095int(here.lng * 1e7), # longitude409633.0000, # altitude4097mavutil.mavlink.MAV_MISSION_TYPE_FENCE),4098self.mav.mav.mission_item_int_encode(4099target_system,4100target_component,41011, # seq4102mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4103mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,41040, # current41050, # autocontinue41065, # p1 - radius41070, # p241080, # p341090, # p44110int(self.offset_location_ne(here, 100, 100).lat * 1e7), # latitude4111int(here.lng * 1e7), # longitude411233.0000, # altitude4113mavutil.mavlink.MAV_MISSION_TYPE_FENCE),4114]4115self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4116items)4117self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz4118self.drain_mav()4119self.assert_fence_breached()4120try:4121self.arm_motors_with_rc_input()4122except NotAchievedException:4123pass4124if self.armed():4125raise NotAchievedException(4126"Armed when within exclusion zone")41274128self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4129[])4130self.wait_fence_not_breached()41314132def test_poly_fence_noarms_inclusion_circle(self, target_system=1, target_component=1):4133self.start_subtest("Ensure not armable when outside an inclusion circle (but within another")41344135here = self.mav.location()41364137items = [4138self.mav.mav.mission_item_int_encode(4139target_system,4140target_component,41410, # seq4142mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4143mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,41440, # current41450, # autocontinue41465, # p1 - radius41470, # p241480, # p341490, # p44150int(here.lat * 1e7), # latitude4151int(here.lng * 1e7), # longitude415233.0000, # altitude4153mavutil.mavlink.MAV_MISSION_TYPE_FENCE),4154self.mav.mav.mission_item_int_encode(4155target_system,4156target_component,41571, # seq4158mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4159mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,41600, # current41610, # autocontinue41625, # p1 - radius41630, # p241640, # p341650, # p44166int(self.offset_location_ne(here, 100, 100).lat * 1e7), # latitude4167int(here.lng * 1e7), # longitude416833.0000, # altitude4169mavutil.mavlink.MAV_MISSION_TYPE_FENCE),4170]4171self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4172items)4173self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz4174self.drain_mav()4175self.assert_fence_breached()4176try:4177self.arm_motors_with_rc_input()4178except NotAchievedException:4179pass4180if self.armed():4181raise NotAchievedException(4182"Armed when outside an inclusion zone")41834184self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4185[])4186self.wait_fence_not_breached()41874188def test_poly_fence_noarms_exclusion_polyfence(self, target_system=1, target_component=1):4189self.start_subtest("Ensure not armable when inside an exclusion polyfence (but outside another")41904191here = self.mav.location()41924193self.upload_fences_from_locations([4194(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4195# east4196self.offset_location_ne(here, -50, 20), # bl4197self.offset_location_ne(here, 50, 20), # br4198self.offset_location_ne(here, 50, 40), # tr4199self.offset_location_ne(here, -50, 40), # tl,4200]),4201(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4202# over the top of the vehicle4203self.offset_location_ne(here, -50, -50), # bl4204self.offset_location_ne(here, -50, 50), # br4205self.offset_location_ne(here, 50, 50), # tr4206self.offset_location_ne(here, 50, -50), # tl,4207]),4208])4209self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz4210self.drain_mav()4211self.assert_fence_breached()4212try:4213self.arm_motors_with_rc_input()4214except NotAchievedException:4215pass4216if self.armed():4217raise NotAchievedException(4218"Armed when within polygon exclusion zone")42194220self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4221[])4222self.wait_fence_not_breached()42234224def test_poly_fence_noarms_inclusion_polyfence(self, target_system=1, target_component=1):4225self.start_subtest("Ensure not armable when outside an inclusion polyfence (but within another")42264227here = self.mav.location()42284229self.upload_fences_from_locations([4230(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [4231# east4232self.offset_location_ne(here, -50, 20), # bl4233self.offset_location_ne(here, 50, 20), # br4234self.offset_location_ne(here, 50, 40), # tr4235self.offset_location_ne(here, -50, 40), # tl,4236]),4237(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [4238# over the top of the vehicle4239self.offset_location_ne(here, -50, -50), # bl4240self.offset_location_ne(here, -50, 50), # br4241self.offset_location_ne(here, 50, 50), # tr4242self.offset_location_ne(here, 50, -50), # tl,4243]),4244])4245self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz4246self.drain_mav()4247self.assert_fence_breached()4248try:4249self.arm_motors_with_rc_input()4250except NotAchievedException:4251pass4252if self.armed():4253raise NotAchievedException(4254"Armed when outside polygon inclusion zone")42554256self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4257[])4258self.wait_fence_not_breached()42594260def test_fence_upload_timeouts_1(self, target_system=1, target_component=1):4261self.start_subtest("fence_upload timeouts 1")4262self.progress("Telling victim there will be one item coming")4263self.mav.mav.mission_count_send(target_system,4264target_component,42651,4266mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4267m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],4268blocking=True,4269timeout=1)4270self.progress("Got (%s)" % str(m))4271if m is None:4272raise NotAchievedException("Did not get ACK or mission request")42734274if m.get_type() == "MISSION_ACK":4275raise NotAchievedException("Expected MISSION_REQUEST")42764277if m.seq != 0:4278raise NotAchievedException("Expected request for seq=0")42794280if m.target_system != self.mav.mav.srcSystem:4281raise NotAchievedException("Incorrect target system in MISSION_REQUEST")4282if m.target_component != self.mav.mav.srcComponent:4283raise NotAchievedException("Incorrect target component in MISSION_REQUEST")4284tstart = self.get_sim_time()4285rerequest_count = 04286received_text = False4287received_ack = False4288while True:4289if received_ack and received_text:4290break4291if self.get_sim_time_cached() - tstart > 10:4292raise NotAchievedException("Did not get expected ack and statustext")4293m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK', 'STATUSTEXT'],4294blocking=True,4295timeout=1)4296self.progress("Got (%s)" % str(m))4297if m is None:4298self.progress("Did not receive any messages")4299continue4300if m.get_type() == "MISSION_REQUEST":4301if m.seq != 0:4302raise NotAchievedException("Received request for invalid seq")4303if m.target_system != self.mav.mav.srcSystem:4304raise NotAchievedException("Incorrect target system in MISSION_REQUEST")4305if m.target_component != self.mav.mav.srcComponent:4306raise NotAchievedException("Incorrect target component in MISSION_REQUEST")4307rerequest_count += 14308self.progress("Valid re-request received.")4309continue4310if m.get_type() == "MISSION_ACK":4311if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE:4312raise NotAchievedException("Wrong mission type")4313if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:4314raise NotAchievedException("Wrong result")4315received_ack = True4316continue4317if m.get_type() == "STATUSTEXT":4318if "upload time" in m.text:4319received_text = True4320continue4321if rerequest_count < 3:4322raise NotAchievedException("Expected several re-requests of mission item")4323self.end_subtest("fence upload timeouts 1")43244325def expect_request_for_item(self, item):4326m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],4327blocking=True,4328timeout=1)4329self.progress("Got (%s)" % str(m))4330if m is None:4331raise NotAchievedException("Did not get ACK or mission request")43324333if m.get_type() == "MISSION_ACK":4334raise NotAchievedException("Expected MISSION_REQUEST")43354336if m.seq != item.seq:4337raise NotAchievedException("Expected request for seq=%u" % item.seq)43384339if m.target_system != self.mav.mav.srcSystem:4340raise NotAchievedException("Incorrect target system in MISSION_REQUEST")4341if m.target_component != self.mav.mav.srcComponent:4342raise NotAchievedException("Incorrect target component in MISSION_REQUEST")43434344def test_fence_upload_timeouts_2(self, target_system=1, target_component=1):4345self.start_subtest("fence upload timeouts 2")4346self.progress("Telling victim there will be two items coming")4347# avoid a timeout race condition where ArduPilot re-requests a4348# fence point before we receive and respond to the first one.4349# Since ArduPilot has a 1s timeout on re-requesting, This only4350# requires a round-trip delay of 1/speedup seconds to trigger4351# - and that has been seen in practise on Travis4352old_speedup = self.get_parameter("SIM_SPEEDUP")4353self.set_parameter("SIM_SPEEDUP", 1)4354self.mav.mav.mission_count_send(target_system,4355target_component,43562,4357mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4358self.progress("Sending item with seq=0")4359item = self.mav.mav.mission_item_int_encode(4360target_system,4361target_component,43620, # seq4363mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4364mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,43650, # current43660, # autocontinue43671, # p1 radius43680, # p243690, # p343700, # p44371int(1.1 * 1e7), # latitude4372int(1.2 * 1e7), # longitude437333.0000, # altitude4374mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4375self.expect_request_for_item(item)4376item.pack(self.mav.mav)4377self.mav.mav.send(item)43784379self.progress("Sending item with seq=1")4380item = self.mav.mav.mission_item_int_encode(4381target_system,4382target_component,43831, # seq4384mavutil.mavlink.MAV_FRAME_GLOBAL_INT,4385mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,43860, # current43870, # autocontinue43881, # p1 radius43890, # p243900, # p343910, # p44392int(1.1 * 1e7), # latitude4393int(1.2 * 1e7), # longitude439433.0000, # altitude4395mavutil.mavlink.MAV_MISSION_TYPE_FENCE)43964397self.expect_request_for_item(item)43984399self.set_parameter("SIM_SPEEDUP", old_speedup)44004401self.progress("Now waiting for a timeout")4402tstart = self.get_sim_time()4403rerequest_count = 04404received_text = False4405received_ack = False4406while True:4407if received_ack and received_text:4408break4409if self.get_sim_time_cached() - tstart > 10:4410raise NotAchievedException("Did not get expected ack and statustext")4411m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK', 'STATUSTEXT'],4412blocking=True,4413timeout=0.1)4414self.progress("Got (%s)" % str(m))4415if m is None:4416self.progress("Did not receive any messages")4417continue4418if m.get_type() == "MISSION_REQUEST":4419if m.seq != 1:4420raise NotAchievedException("Received request for invalid seq")4421if m.target_system != self.mav.mav.srcSystem:4422raise NotAchievedException("Incorrect target system in MISSION_REQUEST")4423if m.target_component != self.mav.mav.srcComponent:4424raise NotAchievedException("Incorrect target component in MISSION_REQUEST")4425rerequest_count += 14426self.progress("Valid re-request received.")4427continue4428if m.get_type() == "MISSION_ACK":4429if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE:4430raise NotAchievedException("Wrong mission type")4431if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:4432raise NotAchievedException("Wrong result")4433received_ack = True4434continue4435if m.get_type() == "STATUSTEXT":4436if "upload time" in m.text:4437received_text = True4438continue4439if rerequest_count < 3:4440raise NotAchievedException("Expected several re-requests of mission item")4441self.end_subtest("fence upload timeouts 2")44424443def test_fence_upload_timeouts(self, target_system=1, target_component=1):4444self.test_fence_upload_timeouts_1(target_system=target_system,4445target_component=target_component)4446self.test_fence_upload_timeouts_2(target_system=target_system,4447target_component=target_component)44484449def test_poly_fence_compatability_ordering(self, target_system=1, target_component=1):4450self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4451target_system=target_system,4452target_component=target_component)4453here = self.mav.location()4454self.progress("try uploading return point last")4455self.roundtrip_fence_using_fencepoint_protocol([4456self.offset_location_ne(here, 0, 0), # bl // return point4457self.offset_location_ne(here, -50, 20), # bl4458self.offset_location_ne(here, 50, 20), # br4459self.offset_location_ne(here, 50, 40), # tr4460self.offset_location_ne(here, -50, 40), # tl,4461self.offset_location_ne(here, -50, 20), # closing point4462], ordering=[1, 2, 3, 4, 5, 0])4463self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4464target_system=target_system,4465target_component=target_component)44664467self.progress("try uploading return point in middle")4468self.roundtrip_fence_using_fencepoint_protocol([4469self.offset_location_ne(here, 0, 0), # bl // return point4470self.offset_location_ne(here, -50, 20), # bl4471self.offset_location_ne(here, 50, 20), # br4472self.offset_location_ne(here, 50, 40), # tr4473self.offset_location_ne(here, -50, 40), # tl,4474self.offset_location_ne(here, -50, 20), # closing point4475], ordering=[1, 2, 3, 0, 4, 5])4476self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4477target_system=target_system,4478target_component=target_component)44794480self.progress("try closing point in middle")4481self.roundtrip_fence_using_fencepoint_protocol([4482self.offset_location_ne(here, 0, 0), # bl // return point4483self.offset_location_ne(here, -50, 20), # bl4484self.offset_location_ne(here, 50, 20), # br4485self.offset_location_ne(here, 50, 40), # tr4486self.offset_location_ne(here, -50, 40), # tl,4487self.offset_location_ne(here, -50, 20), # closing point4488], ordering=[0, 1, 2, 5, 3, 4])4489self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4490target_system=target_system,4491target_component=target_component)44924493# this is expected to fail as we don't return the closing4494# point correctly until the first is uploaded4495# self.progress("try closing point first")4496# failed = False4497# try:4498# self.roundtrip_fence_using_fencepoint_protocol([4499# self.offset_location_ne(here, 0, 0), # bl // return point4500# self.offset_location_ne(here, -50, 20), # bl4501# self.offset_location_ne(here, 50, 20), # br4502# self.offset_location_ne(here, 50, 40), # tr4503# self.offset_location_ne(here, -50, 40), # tl,4504# self.offset_location_ne(here, -50, 20), # closing point4505# ], ordering=[5, 0, 1, 2, 3, 4])4506# except NotAchievedException as e:4507# failed = "got=0.000000 want=" in str(e)4508# if not failed:4509# raise NotAchievedException("Expected failure, did not get it")4510# self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4511# target_system=target_system,4512# target_component=target_component)45134514self.progress("try (almost) reverse order")4515self.roundtrip_fence_using_fencepoint_protocol([4516self.offset_location_ne(here, 0, 0), # bl // return point4517self.offset_location_ne(here, -50, 20), # bl4518self.offset_location_ne(here, 50, 20), # br4519self.offset_location_ne(here, 50, 40), # tr4520self.offset_location_ne(here, -50, 40), # tl,4521self.offset_location_ne(here, -50, 20), # closing point4522], ordering=[4, 3, 2, 1, 0, 5])4523self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4524target_system=target_system,4525target_component=target_component)45264527def test_poly_fence_big_then_small(self, target_system=1, target_component=1):4528here = self.mav.location()45294530self.roundtrip_fence_using_fencepoint_protocol([4531self.offset_location_ne(here, 0, 0), # bl // return point4532self.offset_location_ne(here, -50, 20), # bl4533self.offset_location_ne(here, 50, 20), # br4534self.offset_location_ne(here, 50, 40), # tr4535self.offset_location_ne(here, -50, 40), # tl,4536self.offset_location_ne(here, -50, 20), # closing point4537], ordering=[1, 2, 3, 4, 5, 0])4538downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4539if len(downloaded_items) != 5:4540# that's one return point and then bl, br, tr, then tl4541raise NotAchievedException("Bad number of downloaded items in original download")45424543self.roundtrip_fence_using_fencepoint_protocol([4544self.offset_location_ne(here, 0, 0), # bl // return point4545self.offset_location_ne(here, -50, 20), # bl4546self.offset_location_ne(here, 50, 40), # tr4547self.offset_location_ne(here, -50, 40), # tl,4548self.offset_location_ne(here, -50, 20), # closing point4549], ordering=[1, 2, 3, 4, 0])45504551downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4552want_count = 44553if len(downloaded_items) != want_count:4554# that's one return point and then bl, tr, then tl4555raise NotAchievedException("Bad number of downloaded items in second download got=%u wanted=%u" %4556(len(downloaded_items), want_count))4557downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4558if len(downloaded_items) != 4:4559# that's one return point and then bl, tr, then tl4560raise NotAchievedException("Bad number of downloaded items in second download (second time) got=%u want=%u" %4561(len(downloaded_items), want_count))45624563def test_poly_fence_compatability(self, target_system=1, target_component=1):4564self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,4565target_system=target_system,4566target_component=target_component)45674568self.test_poly_fence_compatability_ordering(target_system=target_system, target_component=target_component)45694570here = self.mav.location()45714572self.progress("Playing with changing point count")4573self.roundtrip_fence_using_fencepoint_protocol(4574[4575self.offset_location_ne(here, 0, 0), # bl // return point4576self.offset_location_ne(here, -50, 20), # bl4577self.offset_location_ne(here, 50, 20), # br4578self.offset_location_ne(here, 50, 40), # tr4579self.offset_location_ne(here, -50, 40), # tl,4580self.offset_location_ne(here, -50, 20), # closing point4581])4582self.roundtrip_fence_using_fencepoint_protocol(4583[4584self.offset_location_ne(here, 0, 0), # bl // return point4585self.offset_location_ne(here, -50, 20), # bl4586self.offset_location_ne(here, 50, 20), # br4587self.offset_location_ne(here, -50, 40), # tl,4588self.offset_location_ne(here, -50, 20), # closing point4589])4590self.roundtrip_fence_using_fencepoint_protocol(4591[4592self.offset_location_ne(here, 0, 0), # bl // return point4593self.offset_location_ne(here, -50, 20), # bl4594self.offset_location_ne(here, 50, 20), # br4595self.offset_location_ne(here, 50, 40), # tr4596self.offset_location_ne(here, -50, 40), # tl,4597self.offset_location_ne(here, -50, 20), # closing point4598])45994600def test_poly_fence_reboot_survivability(self):4601here = self.mav.location()46024603self.upload_fences_from_locations([4604(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4605# east4606self.offset_location_ne(here, -50, 20), # bl4607self.offset_location_ne(here, 50, 20), # br4608self.offset_location_ne(here, 50, 40), # tr4609self.offset_location_ne(here, -50, 40), # tl,4610]),4611(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4612# over the top of the vehicle4613self.offset_location_ne(here, -50, -50), # bl4614self.offset_location_ne(here, -50, 50), # br4615self.offset_location_ne(here, 50, 50), # tr4616self.offset_location_ne(here, 50, -50), # tl,4617]),4618])4619self.reboot_sitl()4620downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)4621downloaded_len = len(downloaded_items)4622if downloaded_len != 8:4623raise NotAchievedException("Items did not survive reboot (want=%u got=%u)" %4624(8, downloaded_len))46254626def PolyFence(self):4627'''test fence-related functions'''4628target_system = 14629target_component = 146304631self.change_mode("LOITER")4632self.wait_ready_to_arm()4633here = self.mav.location()4634self.progress("here: %f %f" % (here.lat, here.lng))4635self.set_parameters({4636"FENCE_ENABLE": 1,4637"AVOID_ENABLE": 0,4638})46394640# self.set_parameter("SIM_SPEEDUP", 1)46414642self.test_poly_fence_big_then_small()46434644self.test_poly_fence_compatability()46454646self.test_fence_upload_timeouts()46474648self.test_poly_fence_noarms(target_system=target_system, target_component=target_component)46494650self.arm_vehicle()46514652self.test_poly_fence_inclusion(here, target_system=target_system, target_component=target_component)4653self.test_poly_fence_exclusion(here, target_system=target_system, target_component=target_component)46544655self.disarm_vehicle()46564657self.test_poly_fence_reboot_survivability()46584659def test_poly_fence_inclusion_overlapping_inclusion_circles(self, here, target_system=1, target_component=1):4660self.start_subtest("Overlapping circular inclusion")4661self.upload_fences_from_locations([4662(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {4663"radius": 30,4664"loc": self.offset_location_ne(here, -20, 0),4665}),4666(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {4667"radius": 30,4668"loc": self.offset_location_ne(here, 20, 0),4669}),4670])4671if self.mavproxy is not None:4672# handy for getting pretty pictures4673self.mavproxy.send("fence list\n")46744675self.delay_sim_time(5)4676self.progress("Drive outside top circle")4677fence_middle = self.offset_location_ne(here, -150, 0)4678self.drive_somewhere_breach_boundary_and_rtl(4679fence_middle,4680target_system=target_system,4681target_component=target_component)46824683self.delay_sim_time(5)4684self.progress("Drive outside bottom circle")4685fence_middle = self.offset_location_ne(here, 150, 0)4686self.drive_somewhere_breach_boundary_and_rtl(4687fence_middle,4688target_system=target_system,4689target_component=target_component)46904691def test_poly_fence_inclusion(self, here, target_system=1, target_component=1):4692self.progress("Circle and Polygon inclusion")4693self.test_poly_fence_inclusion_overlapping_inclusion_circles(4694here,4695target_system=target_system,4696target_component=target_component)46974698self.upload_fences_from_locations([4699(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [4700self.offset_location_ne(here, -40, -20), # tl4701self.offset_location_ne(here, 50, -20), # tr4702self.offset_location_ne(here, 50, 20), # br4703self.offset_location_ne(here, -40, 20), # bl,4704]),4705(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {4706"radius": 30,4707"loc": self.offset_location_ne(here, -20, 0),4708}),4709])47104711self.delay_sim_time(5)4712if self.mavproxy is not None:4713self.mavproxy.send("fence list\n")4714self.progress("Drive outside polygon")4715fence_middle = self.offset_location_ne(here, -150, 0)4716self.drive_somewhere_breach_boundary_and_rtl(4717fence_middle,4718target_system=target_system,4719target_component=target_component)47204721self.delay_sim_time(5)4722self.progress("Drive outside circle")4723fence_middle = self.offset_location_ne(here, 150, 0)4724self.drive_somewhere_breach_boundary_and_rtl(4725fence_middle,4726target_system=target_system,4727target_component=target_component)47284729self.upload_fences_from_locations([4730(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [4731self.offset_location_ne(here, -20, -25), # tl4732self.offset_location_ne(here, 50, -25), # tr4733self.offset_location_ne(here, 50, 15), # br4734self.offset_location_ne(here, -20, 15), # bl,4735]),4736(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [4737self.offset_location_ne(here, 20, -20), # tl4738self.offset_location_ne(here, -50, -20), # tr4739self.offset_location_ne(here, -50, 20), # br4740self.offset_location_ne(here, 20, 20), # bl,4741]),4742])47434744self.delay_sim_time(5)4745if self.mavproxy is not None:4746self.mavproxy.send("fence list\n")4747self.progress("Drive outside top polygon")4748fence_middle = self.offset_location_ne(here, -150, 0)4749self.drive_somewhere_breach_boundary_and_rtl(4750fence_middle,4751target_system=target_system,4752target_component=target_component)47534754self.delay_sim_time(5)4755self.progress("Drive outside bottom polygon")4756fence_middle = self.offset_location_ne(here, 150, 0)4757self.drive_somewhere_breach_boundary_and_rtl(4758fence_middle,4759target_system=target_system,4760target_component=target_component)47614762def test_poly_fence_exclusion(self, here, target_system=1, target_component=1):47634764self.upload_fences_from_locations([4765(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4766# east4767self.offset_location_ne(here, -50, 20), # bl4768self.offset_location_ne(here, 50, 20), # br4769self.offset_location_ne(here, 50, 40), # tr4770self.offset_location_ne(here, -50, 40), # tl,4771]),4772(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4773# west4774self.offset_location_ne(here, -50, -20), # tl4775self.offset_location_ne(here, 50, -20), # tr4776self.offset_location_ne(here, 50, -40), # br4777self.offset_location_ne(here, -50, -40), # bl,4778]),4779(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION, {4780"radius": 30,4781"loc": self.offset_location_ne(here, -60, 0),4782}),4783])4784self.delay_sim_time(5)4785if self.mavproxy is not None:4786self.mavproxy.send("fence list\n")47874788self.progress("Breach eastern boundary")4789fence_middle = self.offset_location_ne(here, 0, 30)4790self.drive_somewhere_breach_boundary_and_rtl(fence_middle,4791target_system=target_system,4792target_component=target_component)47934794self.progress("delaying - hack to work around manual recovery bug")4795self.delay_sim_time(5)47964797self.progress("Breach western boundary")4798fence_middle = self.offset_location_ne(here, 0, -30)4799self.drive_somewhere_breach_boundary_and_rtl(fence_middle,4800target_system=target_system,4801target_component=target_component)48024803self.progress("delaying - hack to work around manual recovery bug")4804self.delay_sim_time(5)48054806self.progress("Breach southern circle")4807fence_middle = self.offset_location_ne(here, -150, 0)4808self.drive_somewhere_breach_boundary_and_rtl(fence_middle,4809target_system=target_system,4810target_component=target_component)48114812def SmartRTL(self):4813'''Test SmartRTL'''4814self.change_mode("STEERING")4815self.wait_ready_to_arm()4816self.arm_vehicle()4817# drive two sides of a square, make sure we don't go back through4818# the middle of the square4819self.progress("Driving North")4820self.reach_heading_manual(0)4821self.set_rc(3, 2000)4822self.delay_sim_time(5)4823self.set_rc(3, 1000)4824self.wait_groundspeed(0, 1)4825loc = self.mav.location()4826self.progress("Driving East")4827self.set_rc(3, 2000)4828self.reach_heading_manual(90)4829self.set_rc(3, 2000)4830self.delay_sim_time(5)4831self.set_rc(3, 1000)48324833self.progress("Entering smartrtl")4834self.change_mode("SMART_RTL")48354836self.progress("Ensure we go via intermediate point")4837self.wait_distance_to_location(loc, 0, 5, timeout=60)48384839self.progress("Ensure we get home")4840self.wait_distance_to_home(3, 7, timeout=30)48414842self.disarm_vehicle()48434844def MotorTest(self):4845'''Motor Test triggered via mavlink'''4846magic_throttle_value = 18124847self.wait_ready_to_arm()4848self.run_cmd(4849mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,4850p1=1, # motor instance4851p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, # throttle type4852p3=magic_throttle_value, # throttle4853p4=5, # timeout4854p5=1, # motor count4855p6=0, # test order (see MOTOR_TEST_ORDER)4856)4857self.wait_armed()4858self.progress("Waiting for magic throttle value")4859self.wait_servo_channel_value(3, magic_throttle_value)4860self.wait_servo_channel_value(3, self.get_parameter("RC3_TRIM", 5), timeout=10)4861self.wait_disarmed()48624863def PolyFenceObjectAvoidanceGuided(self, target_system=1, target_component=1):4864'''PolyFence object avoidance tests - guided mode'''4865if not self.mavproxy_can_do_mision_item_protocols():4866return48674868self.test_poly_fence_object_avoidance_guided_pathfinding(4869target_system=target_system,4870target_component=target_component)4871self.test_poly_fence_object_avoidance_guided_two_squares(4872target_system=target_system,4873target_component=target_component)48744875def PolyFenceObjectAvoidanceAuto(self, target_system=1, target_component=1):4876'''PolyFence object avoidance tests - auto mode'''4877mavproxy = self.start_mavproxy()4878self.load_fence_using_mavproxy(mavproxy, "rover-path-planning-fence.txt")4879self.stop_mavproxy(mavproxy)4880# self.load_fence("rover-path-planning-fence.txt")4881self.load_mission("rover-path-planning-mission.txt")4882self.set_parameters({4883"AVOID_ENABLE": 3,4884"OA_TYPE": 2,4885"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/116014886})4887self.reboot_sitl()4888self.change_mode('AUTO')4889self.wait_ready_to_arm()4890self.arm_vehicle()4891self.set_parameter("FENCE_ENABLE", 1)4892# target_loc is copied from the mission file4893target_loc = mavutil.location(40.073799, -105.229156)4894self.wait_location(target_loc, height_accuracy=None, timeout=300)4895# mission has RTL as last item4896self.wait_distance_to_home(3, 7, timeout=300)4897self.disarm_vehicle()48984899def send_guided_mission_item(self, loc, target_system=1, target_component=1):4900self.mav.mav.mission_item_send(4901target_system,4902target_component,49030,4904mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,4905mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,49062, # current49070, # autocontinue49080, # param149090, # param249100, # param349110, # param44912loc.lat, # x4913loc.lng, # y49140 # z4915)49164917def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, target_component=1):4918self.load_fence("rover-path-planning-fence.txt")4919self.set_parameters({4920"AVOID_ENABLE": 3,4921"OA_TYPE": 2,4922"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/116014923})4924self.reboot_sitl()4925self.change_mode('GUIDED')4926self.wait_ready_to_arm()4927self.arm_vehicle()4928self.set_parameter("FENCE_ENABLE", 1)4929target_loc = mavutil.location(40.073800, -105.229172)4930self.send_guided_mission_item(target_loc,4931target_system=target_system,4932target_component=target_component)4933self.wait_location(target_loc, timeout=300)4934self.do_RTL(timeout=300)4935self.disarm_vehicle()49364937def WheelEncoders(self):4938'''make sure wheel encoders are generally working'''4939self.set_parameters({4940"WENC_TYPE": 10,4941"EK3_ENABLE": 1,4942"AHRS_EKF_TYPE": 3,4943})4944self.reboot_sitl()4945self.change_mode("LOITER")4946self.wait_ready_to_arm()4947self.change_mode("MANUAL")4948self.arm_vehicle()4949self.set_rc(3, 1600)49504951m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5)49524953tstart = self.get_sim_time()4954while True:4955if self.get_sim_time_cached() - tstart > 10:4956break4957dist_home = self.distance_to_home(use_cached_home=True)4958m = self.mav.messages.get("WHEEL_DISTANCE")4959delta = abs(m.distance[0] - dist_home)4960self.progress("dist-home=%f wheel-distance=%f delta=%f" %4961(dist_home, m.distance[0], delta))4962if delta > 5:4963raise NotAchievedException("wheel distance incorrect")4964self.disarm_vehicle()49654966def test_poly_fence_object_avoidance_guided_two_squares(self, target_system=1, target_component=1):4967self.start_subtest("Ensure we can steer around obstacles in guided mode")4968here = self.mav.location()4969self.upload_fences_from_locations([4970(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4971# east4972self.offset_location_ne(here, -50, 20), # bl4973self.offset_location_ne(here, 50, 10), # tl4974self.offset_location_ne(here, 50, 30), # tr4975self.offset_location_ne(here, -50, 40), # br,4976]),4977(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [4978# further east (and south4979self.offset_location_ne(here, -60, 60), # bl4980self.offset_location_ne(here, 40, 70), # tl4981self.offset_location_ne(here, 40, 90), # tr4982self.offset_location_ne(here, -60, 80), # br,4983]),4984])4985if self.mavproxy is not None:4986self.mavproxy.send("fence list\n")4987self.context_push()4988ex = None4989try:4990self.set_parameters({4991"AVOID_ENABLE": 3,4992"OA_TYPE": 2,4993})4994self.reboot_sitl()4995self.change_mode('GUIDED')4996self.wait_ready_to_arm()4997self.set_parameter("FENCE_ENABLE", 1)4998if self.mavproxy is not None:4999self.mavproxy.send("fence list\n")5000self.arm_vehicle()50015002self.change_mode("GUIDED")5003target = mavutil.location(40.071382, -105.228340, 0, 0)5004self.send_guided_mission_item(target,5005target_system=target_system,5006target_component=target_component)5007self.wait_location(target, timeout=300)5008self.do_RTL()5009self.disarm_vehicle()5010except Exception as e:5011self.print_exception_caught(e)5012ex = e5013self.context_pop()5014self.reboot_sitl()5015if ex is not None:5016raise ex50175018def test_poly_fence_avoidance_dont_breach_exclusion(self, target_system=1, target_component=1):5019self.start_subtest("Ensure we stop before breaching an exclusion fence")5020here = self.mav.location()5021self.upload_fences_from_locations([5022(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [5023# east5024self.offset_location_ne(here, -50, 20), # bl5025self.offset_location_ne(here, 50, 20), # br5026self.offset_location_ne(here, 50, 40), # tr5027self.offset_location_ne(here, -50, 40), # tl,5028]),5029(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [5030# west5031self.offset_location_ne(here, -50, -20), # tl5032self.offset_location_ne(here, 50, -20), # tr5033self.offset_location_ne(here, 50, -40), # br5034self.offset_location_ne(here, -50, -40), # bl,5035]),5036(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {5037"radius": 30,5038"loc": self.offset_location_ne(here, -60, 0),5039}),5040])5041if self.mavproxy is not None:5042self.mavproxy.send("fence list\n")5043self.set_parameters({5044"FENCE_ENABLE": 1,5045"AVOID_ENABLE": 3,5046})5047fence_middle = self.offset_location_ne(here, 0, 30)5048# FIXME: this might be nowhere near "here"!5049expected_stopping_point = mavutil.location(40.0713376, -105.2295738, 0, 0)5050self.drive_somewhere_stop_at_boundary(5051fence_middle,5052expected_stopping_point,5053target_system=target_system,5054target_component=target_component,5055expected_distance_epsilon=3)5056self.set_parameter("AVOID_ENABLE", 0)5057self.do_RTL()50585059def do_RTL(self, distance_min=3, distance_max=7, timeout=60):5060self.change_mode("RTL")5061self.wait_distance_to_home(distance_min, distance_max, timeout=timeout)50625063def PolyFenceAvoidance(self, target_system=1, target_component=1):5064'''PolyFence avoidance tests'''5065self.change_mode("LOITER")5066self.wait_ready_to_arm()5067self.arm_vehicle()5068self.change_mode("MANUAL")5069self.reach_heading_manual(180, turn_right=False)5070self.change_mode("GUIDED")50715072self.test_poly_fence_avoidance_dont_breach_exclusion(target_system=target_system, target_component=target_component)50735074self.disarm_vehicle()50755076def PolyFenceObjectAvoidanceBendyRuler(self, target_system=1, target_component=1):5077'''PolyFence object avoidance tests - bendy ruler'''5078self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")5079self.set_parameters({5080"AVOID_ENABLE": 3,5081"OA_TYPE": 1,5082"FENCE_ENABLE": 1,5083"WP_RADIUS": 5,5084})5085self.reboot_sitl()5086self.set_parameters({5087"OA_BR_LOOKAHEAD": 50,5088})5089self.change_mode('GUIDED')5090self.wait_ready_to_arm()5091self.arm_vehicle()5092target_loc = mavutil.location(40.071060, -105.227734, 1584, 0)5093self.send_guided_mission_item(target_loc,5094target_system=target_system,5095target_component=target_component)5096# FIXME: we don't get within WP_RADIUS of our target?!5097self.wait_location(target_loc, timeout=300, accuracy=15)5098self.do_RTL(timeout=300)5099self.disarm_vehicle()51005101def PolyFenceObjectAvoidanceBendyRulerEasierGuided(self, target_system=1, target_component=1):5102'''finish-line issue means we can't complete the harder one. This5103test can go away once we've nailed that one. The only5104difference here is the target point.5105'''5106self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")5107self.set_parameters({5108"AVOID_ENABLE": 3,5109"OA_TYPE": 1,5110"FENCE_ENABLE": 1,5111"WP_RADIUS": 5,5112})5113self.reboot_sitl()5114self.set_parameters({5115"OA_BR_LOOKAHEAD": 60,5116})5117self.change_mode('GUIDED')5118self.wait_ready_to_arm()5119self.arm_vehicle()5120target_loc = mavutil.location(40.071260, -105.227000, 1584, 0)5121self.send_guided_mission_item(target_loc,5122target_system=target_system,5123target_component=target_component)5124# FIXME: we don't get within WP_RADIUS of our target?!5125self.wait_location(target_loc, timeout=300, accuracy=15)5126self.do_RTL(timeout=300)5127self.disarm_vehicle()51285129def PolyFenceObjectAvoidanceBendyRulerEasierAuto(self, target_system=1, target_component=1):5130'''finish-line issue means we can't complete the harder one. This5131test can go away once we've nailed that one. The only5132difference here is the target point.5133'''5134self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")5135self.load_mission("rover-path-bendyruler-mission-easier.txt")51365137self.set_parameters({5138"AVOID_ENABLE": 3,5139"OA_TYPE": 1, # BendyRuler5140"FENCE_ENABLE": 1,5141"WP_RADIUS": 5,5142})5143self.reboot_sitl()5144self.set_parameters({5145"OA_BR_LOOKAHEAD": 60,5146})5147self.change_mode('AUTO')5148self.wait_ready_to_arm()5149self.arm_vehicle()5150target_loc = mavutil.location(40.071260, -105.227000, 1584, 0)5151# target_loc is copied from the mission file5152self.wait_location(target_loc, timeout=300)5153# mission has RTL as last item5154self.wait_distance_to_home(3, 7, timeout=300)5155self.disarm_vehicle()51565157def test_scripting_simple_loop(self):5158self.start_subtest("Scripting simple loop")51595160self.context_push()51615162messages = []51635164def my_message_hook(mav, message):5165if message.get_type() != 'STATUSTEXT':5166return5167messages.append(message)51685169self.install_message_hook_context(my_message_hook)51705171self.set_parameter("SCR_ENABLE", 1)5172self.install_example_script_context("simple_loop.lua")5173self.reboot_sitl()5174self.delay_sim_time(10)51755176self.context_pop()5177self.reboot_sitl()51785179# check all messages to see if we got our message5180count = 05181for m in messages:5182if "hello, world" in m.text:5183count += 15184self.progress("Got %u hellos" % count)5185if count < 3:5186raise NotAchievedException("Expected at least three hellos")51875188def test_scripting_internal_test(self):5189self.start_subtest("Scripting internal test")51905191self.context_push()51925193self.set_parameters({5194"SCR_ENABLE": 1,5195"SCR_HEAP_SIZE": 1024000,5196"SCR_VM_I_COUNT": 1000000,5197})5198self.install_test_modules_context()5199self.install_mavlink_module_context()52005201self.install_test_scripts_context([5202"scripting_test.lua",5203"scripting_require_test_2.lua",5204"math.lua",5205"strings.lua",5206"mavlink_test.lua",5207])52085209self.context_collect('STATUSTEXT')5210self.context_collect('NAMED_VALUE_FLOAT')52115212self.reboot_sitl()52135214for success_text in [5215"Internal tests passed",5216"Require test 2 passed",5217"Math tests passed",5218"String tests passed",5219"Received heartbeat from"5220]:5221self.wait_statustext(success_text, check_context=True)52225223for success_nvf in [5224"test",5225]:5226self.assert_received_message_field_values("NAMED_VALUE_FLOAT", {5227"name": success_nvf,5228}, check_context=True)52295230self.context_pop()5231self.reboot_sitl()52325233def test_scripting_hello_world(self):5234self.start_subtest("Scripting hello world")52355236self.context_push()5237self.context_collect("STATUSTEXT")5238self.set_parameter("SCR_ENABLE", 1)5239self.install_example_script_context("hello_world.lua")5240self.reboot_sitl()52415242self.wait_statustext('hello, world', check_context=True, timeout=30)52435244self.context_pop()5245self.reboot_sitl()52465247def ScriptingSteeringAndThrottle(self):5248'''Scripting test - steering and throttle'''5249self.start_subtest("Scripting square")52505251self.context_push()5252self.install_example_script_context("rover-set-steering-and-throttle.lua")5253self.set_parameter("SCR_ENABLE", 1)5254self.reboot_sitl()52555256self.wait_ready_to_arm()5257self.arm_vehicle()5258self.set_rc(6, 2000)5259tstart = self.get_sim_time()5260while not self.mode_is("HOLD"):5261if self.get_sim_time_cached() - tstart > 30:5262raise NotAchievedException("Did not move to hold")5263m = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=1)5264if m is not None:5265self.progress("Current speed: %f" % m.groundspeed)5266self.disarm_vehicle()52675268self.context_pop()5269self.reboot_sitl()52705271def test_scripting_auxfunc(self):5272self.start_subtest("Scripting aufunc triggering")52735274self.context_push()5275self.context_collect("STATUSTEXT")5276self.set_parameters({5277"SCR_ENABLE": 1,5278"RELAY1_FUNCTION": 1,5279"RELAY1_PIN": 15280})5281self.install_example_script_context("RCIN_test.lua")5282self.reboot_sitl()52835284self.wait_parameter_value("SIM_PIN_MASK", 121)5285self.wait_parameter_value("SIM_PIN_MASK", 123)5286self.wait_parameter_value("SIM_PIN_MASK", 121)52875288self.context_pop()5289self.reboot_sitl()52905291def test_scripting_print_home_and_origin(self):5292self.start_subtest("Scripting print home and origin")52935294self.context_push()52955296self.set_parameter("SCR_ENABLE", 1)5297self.install_example_script_context("ahrs-print-home-and-origin.lua")5298self.reboot_sitl()5299self.wait_ready_to_arm()5300self.wait_statustext("Home - ")5301self.wait_statustext("Origin - ")53025303self.context_pop()5304self.reboot_sitl()53055306def test_scripting_set_home_to_vehicle_location(self):5307self.start_subtest("Scripting set home to vehicle location")53085309self.context_push()5310self.set_parameter("SCR_ENABLE", 1)5311self.install_example_script_context("ahrs-set-home-to-vehicle-location.lua")5312self.reboot_sitl()53135314self.wait_statustext("Home position reset")53155316self.context_pop()5317self.reboot_sitl()53185319def test_scripting_serial_loopback(self):5320self.start_subtest("Scripting serial loopback test")53215322self.context_push()5323self.context_collect('STATUSTEXT')5324self.set_parameters({5325"SCR_ENABLE": 1,5326"SCR_SDEV_EN": 1,5327"SCR_SDEV1_PROTO": 28,5328})5329self.install_test_script_context("serial_loopback.lua")5330self.reboot_sitl()53315332for success_text in [5333"driver -> device good",5334"device -> driver good",5335]:5336self.wait_statustext(success_text, check_context=True)53375338self.context_pop()5339self.reboot_sitl()53405341def Scripting(self):5342'''Scripting test'''5343self.test_scripting_set_home_to_vehicle_location()5344self.test_scripting_print_home_and_origin()5345self.test_scripting_hello_world()5346self.test_scripting_simple_loop()5347self.test_scripting_internal_test()5348self.test_scripting_auxfunc()5349self.test_scripting_serial_loopback()53505351def test_mission_frame(self, frame, target_system=1, target_component=1):5352self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION,5353target_system=target_system,5354target_component=target_component)5355items = [5356# first item is ignored for missions5357self.mav.mav.mission_item_int_encode(5358target_system,5359target_component,53600, # seq5361mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,5362mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,53630, # current53640, # autocontinue53653, # p153660, # p253670, # p353680, # p45369int(1.0000 * 1e7), # latitude5370int(1.0000 * 1e7), # longitude537131.0000, # altitude5372mavutil.mavlink.MAV_MISSION_TYPE_MISSION),5373self.mav.mav.mission_item_int_encode(5374target_system,5375target_component,53761, # seq5377frame,5378mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,53790, # current53800, # autocontinue53813, # p153820, # p253830, # p353840, # p45385int(1.0000 * 1e7), # latitude5386int(1.0000 * 1e7), # longitude538731.0000, # altitude5388mavutil.mavlink.MAV_MISSION_TYPE_MISSION),5389]53905391self.check_mission_upload_download(items)53925393def MissionFrames(self, target_system=1, target_component=1):5394'''Upload/Download of items in different frames'''5395for frame in (mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT,5396mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,5397mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,5398mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,5399mavutil.mavlink.MAV_FRAME_GLOBAL_INT,5400mavutil.mavlink.MAV_FRAME_GLOBAL):5401self.test_mission_frame(frame,5402target_system=1,5403target_component=1)54045405def mavlink_time_boot_ms(self):5406'''returns a time suitable for putting into the time_boot_ms entry in mavlink packets'''5407return int(time.time() * 1000000)54085409def mavlink_time_boot_us(self):5410'''returns a time suitable for putting into the time_boot_ms entry in mavlink packets'''5411return int(time.time() * 1000000000)54125413def ap_proximity_mav_obstacle_distance_send(self, data):5414increment = data.get("increment", 0)5415increment_f = data.get("increment_f", 0.0)5416max_distance = data["max_distance"]5417invalid_distance = max_distance + 1 # per spec5418distances = data["distances"][:]5419distances.extend([invalid_distance] * (72-len(distances)))5420self.mav.mav.obstacle_distance_send(5421self.mavlink_time_boot_us(),5422mavutil.mavlink.MAV_DISTANCE_SENSOR_LASER,5423distances,5424increment,5425data["min_distance"],5426data["max_distance"],5427increment_f,5428data["angle_offset"],5429mavutil.mavlink.MAV_FRAME_BODY_FRD5430)54315432def send_obstacle_distances_expect_distance_sensor_messages(self, obstacle_distances_in, expect_distance_sensor_messages):5433self.delay_sim_time(11) # allow obstacles to time out5434self.do_timesync_roundtrip()5435expect_distance_sensor_messages_copy = expect_distance_sensor_messages[:]5436last_sent = 05437while True:5438now = self.get_sim_time_cached()5439if now - last_sent > 1:5440self.progress("Sending")5441self.ap_proximity_mav_obstacle_distance_send(obstacle_distances_in)5442last_sent = now5443m = self.mav.recv_match(type='DISTANCE_SENSOR', blocking=True, timeout=1)5444self.progress("Got (%s)" % str(m))5445if m is None:5446self.delay_sim_time(1)5447continue5448orientation = m.orientation5449found = False5450if m.current_distance == m.max_distance:5451# ignored5452continue5453for expected_distance_sensor_message in expect_distance_sensor_messages_copy:5454if expected_distance_sensor_message["orientation"] != orientation:5455continue5456found = True5457if not expected_distance_sensor_message.get("__found__", False):5458self.progress("Marking message as found")5459expected_distance_sensor_message["__found__"] = True5460if (m.current_distance - expected_distance_sensor_message["distance"] > 1):5461raise NotAchievedException(5462"Bad distance for orient=%u want=%u got=%u" %5463(orientation, expected_distance_sensor_message["distance"], m.current_distance))5464break5465if not found:5466raise NotAchievedException("Got unexpected DISTANCE_SENSOR message")5467all_found = True5468for expected_distance_sensor_message in expect_distance_sensor_messages_copy:5469if not expected_distance_sensor_message.get("__found__", False):5470self.progress("message still not found (orient=%u" % expected_distance_sensor_message["orientation"])5471all_found = False5472break5473if all_found:5474self.progress("Have now seen all expected messages")5475break54765477def AP_Proximity_MAV(self):5478'''Test MAV proximity backend'''54795480self.set_parameters({5481"PRX1_TYPE": 2, # AP_Proximity_MAV5482"OA_TYPE": 2, # dijkstra5483"OA_DB_OUTPUT": 3, # send all items5484})5485self.reboot_sitl()54865487# 1 laser pointing straight forward:5488self.send_obstacle_distances_expect_distance_sensor_messages(5489{5490"distances": [234],5491"increment_f": 10,5492"angle_offset": 0.0,5493"min_distance": 0,5494"max_distance": 1000, # cm5495}, [5496{"orientation": 0, "distance": 234},5497])54985499# 5 lasers at front of vehicle, spread over 40 degrees:5500self.send_obstacle_distances_expect_distance_sensor_messages(5501{5502"distances": [111, 222, 333, 444, 555],5503"increment_f": 10,5504"angle_offset": -20.0,5505"min_distance": 0,5506"max_distance": 1000, # cm5507}, [5508{"orientation": 0, "distance": 111},5509])55105511# lots of dense readings (e.g. vision camera:5512distances = [0] * 725513for i in range(0, 72):5514distances[i] = 1000 + 10*abs(36-i)55155516self.send_obstacle_distances_expect_distance_sensor_messages(5517{5518"distances": distances,5519"increment_f": 90/72.0,5520"angle_offset": -45.0,5521"min_distance": 0,5522"max_distance": 2000, # cm5523}, [5524{"orientation": 0, "distance": 1000},5525{"orientation": 1, "distance": 1190},5526{"orientation": 7, "distance": 1190},5527])55285529def SendToComponents(self):5530'''Test ArduPilot send_to_components function'''5531self.set_parameter("CAM1_TYPE", 5) # Camera with MAVlink trigger5532self.reboot_sitl() # needed for CAM1_TYPE to take effect5533self.progress("Introducing ourselves to the autopilot as a component")5534old_srcSystem = self.mav.mav.srcSystem5535self.mav.mav.srcSystem = 15536self.mav.mav.heartbeat_send(5537mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,5538mavutil.mavlink.MAV_AUTOPILOT_INVALID,55390,55400,55410)55425543self.progress("Sending control message")5544self.context_push()5545self.context_collect('COMMAND_LONG')5546self.mav.mav.digicam_control_send(55471, # target_system55481, # target_component55491, # start or keep it up55501, # zoom_pos55510, # zoom_step55520, # focus_lock55530, # 1 shot or start filming555417, # command id (de-dupe field)55550, # extra_param55560.0, # extra_value5557)5558self.mav.mav.srcSystem = old_srcSystem55595560self.assert_received_message_field_values('COMMAND_LONG', {5561'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,5562'param6': 17,5563}, timeout=2, check_context=True)5564self.context_pop()55655566# test sending via commands:5567for run_cmd in self.run_cmd, self.run_cmd_int:5568self.progress("Sending control command")5569self.context_push()5570self.context_collect('COMMAND_LONG')5571run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,5572p1=1, # start or keep it up5573p2=1, # zoom_pos5574p3=0, # zoom_step5575p4=0, # focus_lock5576p5=0, # 1 shot or start filming5577p6=37, # command id (de-dupe field)5578)55795580self.assert_received_message_field_values('COMMAND_LONG', {5581'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,5582'param6': 37,5583}, timeout=2, check_context=True)55845585self.context_pop()55865587# test sending via commands:5588for run_cmd in self.run_cmd, self.run_cmd_int:5589self.progress("Sending configure command")5590self.context_push()5591self.context_collect('COMMAND_LONG')5592run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,5593p1=1,5594p2=1,5595p3=0,5596p4=0,5597p5=12,5598p6=375599)56005601self.assert_received_message_field_values('COMMAND_LONG', {5602'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,5603'param5': 12,5604'param6': 37,5605}, timeout=2, check_context=True)56065607self.context_pop()56085609self.mav.mav.srcSystem = old_srcSystem56105611def SkidSteer(self):5612'''Check skid-steering'''5613model = "rover-skid"56145615self.customise_SITL_commandline([],5616model=model,5617defaults_filepath=self.model_defaults_filepath(model))56185619self.change_mode("MANUAL")5620self.wait_ready_to_arm()5621self.arm_vehicle()5622self.progress("get a known heading to avoid worrying about wrap")5623# this is steering-type-two-paddles5624self.set_rc(1, 1400)5625self.set_rc(3, 1500)5626self.wait_heading(90)5627self.progress("straighten up")5628self.set_rc(1, 1500)5629self.set_rc(3, 1500)5630self.progress("steer one way")5631self.set_rc(1, 1600)5632self.set_rc(3, 1400)5633self.wait_heading(120)5634self.progress("steer the other")5635self.set_rc(1, 1400)5636self.set_rc(3, 1600)5637self.wait_heading(60)5638self.zero_throttle()5639self.disarm_vehicle()56405641def SlewRate(self):5642"""Test Motor Slew Rate feature."""5643self.context_push()5644self.change_mode("MANUAL")5645self.wait_ready_to_arm()5646self.arm_vehicle()56475648self.start_subtest("Test no slew behavior")5649throttle_channel = 35650throttle_max = 20005651self.set_parameter("MOT_SLEWRATE", 0)5652self.set_rc(throttle_channel, throttle_max)5653tstart = self.get_sim_time()5654self.wait_servo_channel_value(throttle_channel, throttle_max)5655tstop = self.get_sim_time()5656achieved_time = tstop - tstart5657self.progress("achieved_time: %0.1fs" % achieved_time)5658if achieved_time > 0.5:5659raise NotAchievedException("Output response should be instant, got %f" % achieved_time)5660self.zero_throttle()5661self.wait_groundspeed(0, 0.5) # why do we not stop?!56625663self.start_subtest("Test 100% slew rate")5664self.set_parameter("MOT_SLEWRATE", 100)5665self.set_rc(throttle_channel, throttle_max)5666tstart = self.get_sim_time()5667self.wait_servo_channel_value(throttle_channel, throttle_max)5668tstop = self.get_sim_time()5669achieved_time = tstop - tstart5670self.progress("achieved_time: %0.1fs" % achieved_time)5671if achieved_time < 0.9 or achieved_time > 1.1:5672raise NotAchievedException("Output response should be 1s, got %f" % achieved_time)5673self.zero_throttle()5674self.wait_groundspeed(0, 0.5) # why do we not stop?!56755676self.start_subtest("Test 50% slew rate")5677self.set_parameter("MOT_SLEWRATE", 50)5678self.set_rc(throttle_channel, throttle_max)5679tstart = self.get_sim_time()5680self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=10)5681tstop = self.get_sim_time()5682achieved_time = tstop - tstart5683self.progress("achieved_time: %0.1fs" % achieved_time)5684if achieved_time < 1.8 or achieved_time > 2.2:5685raise NotAchievedException("Output response should be 2s, got %f" % achieved_time)5686self.zero_throttle()5687self.wait_groundspeed(0, 0.5) # why do we not stop?!56885689self.start_subtest("Test 25% slew rate")5690self.set_parameter("MOT_SLEWRATE", 25)5691self.set_rc(throttle_channel, throttle_max)5692tstart = self.get_sim_time()5693self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=10)5694tstop = self.get_sim_time()5695achieved_time = tstop - tstart5696self.progress("achieved_time: %0.1fs" % achieved_time)5697if achieved_time < 3.6 or achieved_time > 4.4:5698raise NotAchievedException("Output response should be 4s, got %f" % achieved_time)5699self.zero_throttle()5700self.wait_groundspeed(0, 0.5) # why do we not stop?!57015702self.start_subtest("Test 10% slew rate")5703self.set_parameter("MOT_SLEWRATE", 10)5704self.set_rc(throttle_channel, throttle_max)5705tstart = self.get_sim_time()5706self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=20)5707tstop = self.get_sim_time()5708achieved_time = tstop - tstart5709self.progress("achieved_time: %0.1fs" % achieved_time)5710if achieved_time < 9 or achieved_time > 11:5711raise NotAchievedException("Output response should be 10s, got %f" % achieved_time)5712self.zero_throttle()5713self.wait_groundspeed(0, 0.5) # why do we not stop?!5714self.disarm_vehicle()5715self.context_pop()57165717def SET_ATTITUDE_TARGET(self, target_sysid=None, target_compid=1):5718'''Test handling of SET_ATTITUDE_TARGET'''5719if target_sysid is None:5720target_sysid = self.sysid_thismav()5721self.change_mode('GUIDED')5722self.wait_ready_to_arm()5723self.arm_vehicle()5724tstart = self.get_sim_time()5725while True:5726now = self.get_sim_time_cached()5727if now - tstart > 10:5728raise AutoTestTimeoutException("Didn't get to speed")5729self.mav.mav.set_attitude_target_send(57300, # time_boot_ms5731target_sysid,5732target_compid,5733mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |5734mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE |5735mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE,5736mavextra.euler_to_quat([0,5737math.radians(0),5738math.radians(0)]), # att57390, # yaw rate (rad/s)57400, # pitch rate57410, # yaw rate57421) # thrust57435744msg = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=1)5745if msg is None:5746raise NotAchievedException("No VFR_HUD message")5747if msg.groundspeed > 5:5748break5749self.disarm_vehicle()57505751def SET_ATTITUDE_TARGET_heading(self, target_sysid=None, target_compid=1):5752'''Test handling of SET_ATTITUDE_TARGET'''5753self.change_mode('GUIDED')5754self.wait_ready_to_arm()5755self.arm_vehicle()57565757for angle in 0, 290, 70, 180, 0:5758self.SET_ATTITUDE_TARGET_heading_test_target(angle, target_sysid, target_compid)5759self.disarm_vehicle()57605761def SET_ATTITUDE_TARGET_heading_test_target(self, angle, target_sysid, target_compid):5762if target_sysid is None:5763target_sysid = self.sysid_thismav()57645765def poke_set_attitude(value, target):5766self.mav.mav.set_attitude_target_send(57670, # time_boot_ms5768target_sysid,5769target_compid,5770mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |5771mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE |5772mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE,5773mavextra.euler_to_quat([5774math.radians(0),5775math.radians(0),5776math.radians(angle)5777]), # att57780, # roll rate (rad/s)57790, # pitch rate57800, # yaw rate57811) # thrust57825783self.wait_heading(angle, called_function=poke_set_attitude, minimum_duration=5)57845785def SET_POSITION_TARGET_LOCAL_NED(self, target_sysid=None, target_compid=1):5786'''Test handling of SET_POSITION_TARGET_LOCAL_NED'''5787if target_sysid is None:5788target_sysid = self.sysid_thismav()5789self.change_mode('GUIDED')5790self.wait_ready_to_arm()5791self.arm_vehicle()5792ofs_x = 30.05793ofs_y = 30.057945795def send_target():5796self.mav.mav.set_position_target_local_ned_send(57970, # time_boot_ms5798target_sysid,5799target_compid,5800mavutil.mavlink.MAV_FRAME_LOCAL_NED,5801mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |5802mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |5803mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |5804mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |5805mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |5806mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |5807mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |5808mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,5809ofs_x, # pos-x5810ofs_y, # pos-y58110, # pos-z58120, # vel-x58130, # vel-y58140, # vel-z58150, # acc-x58160, # acc-y58170, # acc-z58180, # yaw58190, # yaw rate5820)58215822self.wait_distance_to_local_position(5823(ofs_x, ofs_y, 0),5824distance_min=0,5825distance_max=3,5826timeout=60,5827called_function=lambda last_value, target : send_target(),5828minimum_duration=5, # make sure we stop!5829)58305831self.do_RTL()5832self.disarm_vehicle()58335834def EndMissionBehavior(self, timeout=60):5835'''Test end mission behavior'''5836self.context_push()58375838self.load_mission("end-mission.txt")5839self.wait_ready_to_arm()5840self.arm_vehicle()58415842self.start_subtest("Test End Mission Behavior HOLD")5843self.context_collect("STATUSTEXT")5844self.change_mode("AUTO")5845self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)5846# On Hold we should just stop and don't update the navigation target anymore5847tstart = self.get_sim_time()5848while True:5849if self.get_sim_time_cached() - tstart > 15:5850raise AutoTestTimeoutException("Still getting POSITION_TARGET_GLOBAL_INT")5851m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",5852blocking=True,5853timeout=10)5854if m is None:5855self.progress("No POSITION_TARGET_GLOBAL_INT received, all good !")5856break5857self.context_clear_collection("STATUSTEXT")5858self.change_mode("GUIDED")5859self.context_collect("STATUSTEXT")58605861self.start_subtest("Test End Mission Behavior LOITER")5862self.set_parameter("MIS_DONE_BEHAVE", 1)5863self.change_mode("AUTO")5864self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)5865# On LOITER we should update the navigation target5866tstart = self.get_sim_time()5867while True:5868if self.get_sim_time_cached() - tstart > 15:5869raise AutoTestTimeoutException("Not getting POSITION_TARGET_GLOBAL_INT")5870m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",5871blocking=True,5872timeout=5)5873if m is None:5874self.progress("No POSITION_TARGET_GLOBAL_INT received")5875continue5876else:5877if self.get_sim_time_cached() - tstart > 15:5878self.progress("Got POSITION_TARGET_GLOBAL_INT, all good !")5879break58805881self.start_subtest("Test End Mission Behavior ACRO")5882self.set_parameter("MIS_DONE_BEHAVE", 2)5883# race conditions here to do with get_sim_time()5884# swallowing heartbeats means we have to be a little5885# circuitous when testing here:5886self.change_mode("GUIDED")5887self.send_cmd_do_set_mode('AUTO')5888self.wait_mode("ACRO")58895890self.start_subtest("Test End Mission Behavior MANUAL")5891self.set_parameter("MIS_DONE_BEHAVE", 3)5892# race conditions here to do with get_sim_time()5893# swallowing heartbeats means we have to be a little5894# circuitous when testing here:5895self.change_mode("GUIDED")5896self.send_cmd_do_set_mode("AUTO")5897self.wait_mode("MANUAL")5898self.disarm_vehicle()58995900self.context_pop()5901self.reboot_sitl()59025903def MAVProxyParam(self):5904'''Test MAVProxy parameter handling'''5905mavproxy = self.start_mavproxy()5906mavproxy.send("param fetch\n")5907mavproxy.expect("Received [0-9]+ parameters")5908self.stop_mavproxy(mavproxy)59095910def MAV_CMD_DO_SET_MISSION_CURRENT_mission(self, target_system=1, target_component=1):5911return copy.copy([5912self.mav.mav.mission_item_int_encode(5913target_system,5914target_component,59150, # seq5916mavutil.mavlink.MAV_FRAME_GLOBAL_INT,5917mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,59180, # current59190, # autocontinue59203, # p159210, # p259220, # p359230, # p45924int(1.0000 * 1e7), # latitude5925int(1.0000 * 1e7), # longitude592631.0000, # altitude5927mavutil.mavlink.MAV_MISSION_TYPE_MISSION),5928self.mav.mav.mission_item_int_encode(5929target_system,5930target_component,59311, # seq5932mavutil.mavlink.MAV_FRAME_GLOBAL_INT,5933mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,59340, # current59350, # autocontinue59363, # p159370, # p259380, # p359390, # p45940int(1.0000 * 1e7), # latitude5941int(1.0000 * 1e7), # longitude594231.0000, # altitude5943mavutil.mavlink.MAV_MISSION_TYPE_MISSION),5944self.mav.mav.mission_item_int_encode(5945target_system,5946target_component,59472, # seq5948mavutil.mavlink.MAV_FRAME_GLOBAL_INT,5949mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,59500, # current59510, # autocontinue59523, # p159530, # p259540, # p359550, # p45956int(1.0000 * 1e7), # latitude5957int(1.0000 * 1e7), # longitude595831.0000, # altitude5959mavutil.mavlink.MAV_MISSION_TYPE_MISSION),5960])59615962def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1):5963'''Test handling of CMD_DO_SET_MISSION_CURRENT'''5964if target_sysid is None:5965target_sysid = self.sysid_thismav()5966self.check_mission_upload_download(self.MAV_CMD_DO_SET_MISSION_CURRENT_mission())59675968self.set_current_waypoint(2)59695970self.set_current_waypoint_using_mav_cmd_do_set_mission_current(2)59715972self.run_cmd(5973mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,5974p1=17,5975timeout=1,5976target_sysid=target_sysid,5977target_compid=target_compid,5978want_result=mavutil.mavlink.MAV_RESULT_DENIED,5979)59805981def FlashStorage(self):5982'''Test flash storage (for parameters etc)'''5983self.set_parameter("LOG_BITMASK", 1)5984self.reboot_sitl()59855986self.customise_SITL_commandline([5987"--set-storage-posix-enabled", "0",5988"--set-storage-flash-enabled", "1",5989])5990if self.get_parameter("LOG_BITMASK") == 1:5991raise NotAchievedException("not using flash storage?")5992self.set_parameter("LOG_BITMASK", 2)5993self.reboot_sitl()5994self.assert_parameter_value("LOG_BITMASK", 2)5995self.set_parameter("LOG_BITMASK", 3)5996self.reboot_sitl()5997self.assert_parameter_value("LOG_BITMASK", 3)59985999self.customise_SITL_commandline([])6000# make sure we're back at our original value:6001self.assert_parameter_value("LOG_BITMASK", 1)60026003def FRAMStorage(self):6004'''Test FRAM storage (for parameters etc)'''6005self.set_parameter("LOG_BITMASK", 1)6006self.reboot_sitl()60076008self.customise_SITL_commandline([6009"--set-storage-posix-enabled", "0",6010"--set-storage-fram-enabled", "1",6011])6012# TODO: ensure w'ere actually taking stuff from flash storage:6013# if self.get_parameter("LOG_BITMASK") == 1:6014# raise NotAchievedException("not using flash storage?")6015self.set_parameter("LOG_BITMASK", 2)6016self.reboot_sitl()6017self.assert_parameter_value("LOG_BITMASK", 2)6018self.set_parameter("LOG_BITMASK", 3)6019self.reboot_sitl()6020self.assert_parameter_value("LOG_BITMASK", 3)60216022self.customise_SITL_commandline([])6023# make sure we're back at our original value:6024self.assert_parameter_value("LOG_BITMASK", 1)60256026def RangeFinder(self):6027'''Test RangeFinder'''6028# the following magic numbers correspond to the post locations in SITL6029home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 231)60306031rangefinder_params = {6032"SIM_SONAR_ROT": 0,6033}6034rangefinder_params.update(self.analog_rangefinder_parameters())60356036self.set_parameters(rangefinder_params)6037self.customise_SITL_commandline([6038"--home", home_string,6039])6040self.wait_ready_to_arm()6041if self.mavproxy is not None:6042self.mavproxy.send('script /tmp/post-locations.scr\n')6043m = self.assert_receive_message('RANGEFINDER', very_verbose=True)6044if m.voltage == 0:6045raise NotAchievedException("Did not get non-zero voltage")6046want_range = 106047if abs(m.distance - want_range) > 0.5:6048raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance))60496050def DepthFinder(self):6051'''Test mulitple depthfinders for boats'''6052# Setup rangefinders6053self.customise_SITL_commandline([6054"--serial7=sim:nmea", # NMEA Rangefinder6055])60566057# RANGEFINDER_INSTANCES = [0, 2, 5]6058self.set_parameters({6059"RNGFND1_TYPE" : 17, # NMEA must attach uart to SITL6060"RNGFND1_ORIENT" : 25, # Set to downward facing6061"SERIAL7_PROTOCOL" : 9, # Rangefinder on serial76062"SERIAL7_BAUD" : 9600, # Rangefinder specific baudrate60636064"RNGFND3_TYPE" : 2, # MaxbotixI2C6065"RNGFND3_ADDR" : 112, # 0x70 address from SIM_I2C.cpp6066"RNGFND3_ORIENT" : 0, # Set to forward facing, thus we should not receive DPTH messages from this one60676068"RNGFND6_ADDR" : 113, # 0x71 address from SIM_I2C.cpp6069"RNGFND6_ORIENT" : 25, # Set to downward facing6070"RNGFND6_TYPE" : 2, # MaxbotixI2C6071})60726073self.reboot_sitl()6074self.wait_ready_to_arm()60756076# should not get WATER_DEPTH messages or DPTH logs when the FRAME_CLASS is not a boat6077m = self.mav.recv_match(type="WATER_DEPTH", blocking=True, timeout=2)6078if m is not None:6079raise NotAchievedException("WATER_DEPTH: received message when FRAME_CLASS not a Boat")60806081# Set FRAME_CLASS to start receiving WATER_DEPTH messages & logging DPTH6082self.set_parameters({6083"FRAME_CLASS": 2, # Boat6084})60856086# Check each rangefinder instance is in collection6087rangefinder = [None, None, None, None, None, None] # Be lazy FIXME only need [3]60886089def check_rangefinder(mav, m):6090if m.get_type() != 'WATER_DEPTH':6091return60926093id = m.id60946095# Should not find instance 3 as it is forward facing6096if id == 2:6097raise NotAchievedException("Depthfinder Instance %i with non-downward orientation found" % (id))60986099rangefinder[id] = True61006101if id == 0:6102if float(m.temperature) == 0.0:6103raise NotAchievedException("Depthfinder Instance %i NMEA with temperature not found" % (id))6104elif id == 5:6105if float(m.temperature) != 0.0:6106raise NotAchievedException("Depthfinder Instance %i should not have temperature" % (id))61076108self.wait_ready_to_arm()6109self.arm_vehicle()61106111self.install_message_hook_context(check_rangefinder)6112self.drive_mission("rover1.txt", strict=False)61136114if rangefinder[0] is None:6115raise NotAchievedException("Never saw Depthfinder 1")6116if rangefinder[2] is not None:6117raise NotAchievedException("Should not have found a Depthfinder 3")6118if rangefinder[5] is None:6119raise NotAchievedException("Never saw Depthfinder 6")6120if not self.current_onboard_log_contains_message("DPTH"):6121raise NotAchievedException("Expected DPTH log message")61226123self.progress("Ensuring we get WATER_DEPTH at 12Hz with 2 backends")6124self.set_message_rate_hz('WATER_DEPTH', 12)6125self.assert_message_rate_hz('WATER_DEPTH', 12)61266127def EStopAtBoot(self):6128'''Ensure EStop prevents arming when asserted at boot time'''6129self.context_push()6130self.set_parameters({6131"RC9_OPTION": 31,6132})6133self.set_rc(9, 2000)6134self.reboot_sitl()6135self.assert_prearm_failure(6136"Motors Emergency Stopped",6137other_prearm_failures_fatal=False)6138self.context_pop()6139self.reboot_sitl()61406141def assert_mode(self, mode):6142if not self.mode_is(mode):6143raise NotAchievedException("Mode is not %s" % str(mode))61446145def ChangeModeByNumber(self):6146'''ensure we can set a mode by number, handy when we don't have a6147pymavlink number for it yet'''6148for (x, want) in (0, 'MANUAL'), (1, 'ACRO'), (3, 3):6149self.change_mode(x)6150self.assert_mode(want)61516152def StickMixingAuto(self):6153'''Ensure Stick Mixing works in auto'''6154items = []6155self.set_parameter('STICK_MIXING', 1)6156# home6157items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0),)6158# 1 waypoint a long way away6159items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),)6160self.upload_simple_relhome_mission(items)6161if self.mavproxy is not None:6162# handy for getting pretty pictures6163self.mavproxy.send("wp list\n")6164self.change_mode('AUTO')6165self.wait_ready_to_arm()6166self.arm_vehicle()6167self.set_rc(1, 1150)6168self.wait_heading(45)6169self.wait_heading(90)6170self.disarm_vehicle()61716172def AutoDock(self):6173'''Test automatic docking of rover for multiple FOVs of simulated beacon'''6174self.set_parameters({6175"PLND_ENABLED": 1,6176"PLND_TYPE": 4,6177"PLND_ORIENT": 0,6178})61796180start = self.mav.location()6181target = self.offset_location_ne(start, 50, 0)6182self.progress("Setting target to %f %f" % (start.lat, start.lng))6183stopping_dist = 0.561846185self.set_parameters({6186"SIM_PLD_ENABLE": 1,6187"SIM_PLD_LAT": target.lat,6188"SIM_PLD_LON": target.lng,6189"SIM_PLD_HEIGHT": 0,6190"SIM_PLD_ALT_LMT": 30,6191"SIM_PLD_DIST_LMT": 30,6192"SIM_PLD_ORIENT": 4, # emit beams towards south, vehicle's heading must be north to see it6193"SIM_PLD_OPTIONS": 1,6194"DOCK_SPEED": 2,6195"DOCK_STOP_DIST": stopping_dist,6196})61976198for type in range(0, 3): # CYLINDRICAL FOV, CONICAL FOV, SPHERICAL FOV6199self.set_parameter("SIM_PLD_TYPE", type)6200self.reboot_sitl()6201self.change_mode('GUIDED')6202self.wait_ready_to_arm()6203self.arm_vehicle()6204initial_position = self.offset_location_ne(target, -20, -2)6205self.drive_to_location(initial_position)6206self.change_mode(8) # DOCK mode6207max_delta = 16208self.wait_distance_to_location(target, 0, max_delta, timeout=180)6209self.disarm_vehicle()6210self.assert_receive_message('GLOBAL_POSITION_INT')6211new_pos = self.mav.location()6212delta = abs(self.get_distance(target, new_pos) - stopping_dist)6213self.progress("Docked %f metres from stopping point" % delta)6214if delta > max_delta:6215raise NotAchievedException("Did not dock close enough to stopping point (%fm > %fm" % (delta, max_delta))62166217if not self.current_onboard_log_contains_message("PL"):6218raise NotAchievedException("Did not see expected PL message")62196220self.progress("All done")62216222def PrivateChannel(self):6223'''test the serial option bit specifying a mavlink channel as private'''6224global mav26225port = self.adjust_ardupilot_port(5763)6226mav2 = mavutil.mavlink_connection("tcp:localhost:%u" % port,6227robust_parsing=True,6228source_system=7,6229source_component=7)6230# send a heartbeat or two to make sure ArduPilot's aware:62316232def heartbeat_on_mav2(mav, m):6233'''send a heartbeat on mav2 whenever we get one on mav'''6234global mav26235if mav == mav2:6236return6237if m.get_type() == 'HEARTBEAT':6238mav2.mav.heartbeat_send(6239mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,6240mavutil.mavlink.MAV_AUTOPILOT_INVALID,62410,62420,62430)6244return62456246self.assert_receive_message("HEARTBEAT", mav=mav2)62476248# ensure a targetted message is received:6249self.install_message_hook_context(heartbeat_on_mav2)62506251self.progress("Ensuring we can get a message normally")6252self.poll_message("AUTOPILOT_VERSION", mav=mav2)62536254self.progress("Polling AUTOPILOT_VERSION from random sysid")6255self.send_poll_message("AUTOPILOT_VERSION", mav=mav2, target_sysid=134)6256self.assert_not_receive_message("AUTOPILOT_VERSION", mav=mav2, timeout=10)62576258# make sure we get heartbeats on the main channel from the non-private mav2:6259tstart = self.get_sim_time()6260while True:6261if self.get_sim_time_cached() - tstart > 5:6262raise NotAchievedException("Did not get expected heartbeat from %u" % 7)6263m = self.assert_receive_message("HEARTBEAT")6264if m.get_srcSystem() == 7:6265self.progress("Got heartbeat from (%u) on non-private channel" % 7)6266break62676268# make sure we receive heartbeats from the autotest suite into6269# the component:6270tstart = self.get_sim_time()6271while True:6272if self.get_sim_time_cached() - tstart > 5:6273raise NotAchievedException("Did not get expected heartbeat from %u" % self.mav.source_system)6274m = self.assert_receive_message("HEARTBEAT", mav=mav2)6275if m.get_srcSystem() == self.mav.source_system:6276self.progress("Got heartbeat from (%u) on non-private channel" % self.mav.source_system)6277break62786279def printmessage(mav, m):6280global mav26281if mav == mav2:6282return62836284print("Got (%u/%u) (%s) " % (m.get_srcSystem(), m.get_srcComponent(), str(m)))62856286# self.install_message_hook_context(printmessage)62876288# ensure setting the private channel mask doesn't cause us to6289# execute these commands:6290self.set_parameter("SERIAL2_OPTIONS", 1024)6291self.reboot_sitl() # mavlink-private is reboot-required6292mav2 = mavutil.mavlink_connection("tcp:localhost:5763",6293robust_parsing=True,6294source_system=7,6295source_component=7)6296# self.send_debug_trap()6297self.send_poll_message("AUTOPILOT_VERSION", mav=mav2, target_sysid=134)6298self.assert_not_receive_message("AUTOPILOT_VERSION", mav=mav2, timeout=10)62996300# make sure messages from a private channel don't make it to6301# the main channel:6302self.drain_mav(self.mav)6303self.drain_mav(mav2)63046305# make sure we do NOT get heartbeats on the main channel from6306# the private mav2:6307tstart = self.get_sim_time()6308while True:6309if self.get_sim_time_cached() - tstart > 5:6310break6311m = self.assert_receive_message("HEARTBEAT")6312if m.get_srcSystem() == 7:6313raise NotAchievedException("Got heartbeat from private channel")63146315self.progress("ensure no outside heartbeats reach private channels")6316tstart = self.get_sim_time()6317while True:6318if self.get_sim_time_cached() - tstart > 5:6319break6320m = self.assert_receive_message("HEARTBEAT")6321if m.get_srcSystem() == 1 and m.get_srcComponent() == 1:6322continue6323# note the above test which shows we get heartbeats from6324# both the vehicle and this tests's special heartbeat6325raise NotAchievedException("Got heartbeat on private channel from non-vehicle")63266327def MAV_CMD_DO_SET_REVERSE(self):6328'''test MAV_CMD_DO_SET_REVERSE command'''6329self.change_mode('GUIDED')6330self.wait_ready_to_arm()6331self.arm_vehicle()63326333here = self.mav.location()6334target_loc = self.offset_location_ne(here, 2000, 0)6335self.send_guided_mission_item(target_loc)63366337self.wait_groundspeed(3, 100, minimum_duration=5)63386339for method in self.run_cmd, self.run_cmd_int:6340self.progress("Forwards!")6341method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0)6342self.wait_heading(0)63436344self.progress("Backwards!")6345method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=1)6346self.wait_heading(180)63476348self.progress("Forwards!")6349method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0)6350self.wait_heading(0)63516352self.disarm_vehicle()63536354def MAV_CMD_NAV_RETURN_TO_LAUNCH(self):6355'''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command'''6356self.change_mode('GUIDED')6357self.wait_ready_to_arm()6358self.arm_vehicle()63596360here = self.mav.location()6361target_loc = self.offset_location_ne(here, 2000, 0)6362self.send_guided_mission_item(target_loc)6363self.wait_distance_to_home(20, 100)63646365self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)6366self.wait_mode('RTL')63676368self.change_mode('GUIDED')63696370self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)6371self.wait_mode('RTL')63726373self.wait_distance_to_home(0, 5, timeout=30)6374self.disarm_vehicle()63756376def MAV_CMD_DO_CHANGE_SPEED(self):6377'''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command'''6378self.change_mode('GUIDED')6379self.wait_ready_to_arm()6380self.arm_vehicle()63816382original_loc = self.mav.location()6383here = original_loc6384target_loc = self.offset_location_ne(here, 2000, 0)6385self.send_guided_mission_item(target_loc)6386self.wait_distance_to_home(20, 100)63876388speeds = 3, 7, 12, 463896390for speed in speeds:6391self.run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)6392self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5)63936394self.send_guided_mission_item(original_loc)63956396for speed in speeds:6397self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)6398self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5)63996400self.change_mode('RTL')64016402self.wait_distance_to_home(0, 5, timeout=30)6403self.disarm_vehicle()64046405def MAV_CMD_MISSION_START(self):6406'''simple test for starting missing using this command'''6407# home and 1 waypoint a long way away:6408self.upload_simple_relhome_mission([6409(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0),6410(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),6411])6412self.change_mode('AUTO')6413self.wait_ready_to_arm()6414self.arm_vehicle()6415for method in self.run_cmd, self.run_cmd_int:6416self.change_mode('MANUAL')6417self.wait_groundspeed(0, 1)6418method(mavutil.mavlink.MAV_CMD_MISSION_START)6419self.wait_mode('AUTO')6420self.wait_groundspeed(3, 100)6421self.disarm_vehicle()64226423def MAV_CMD_NAV_SET_YAW_SPEED(self):6424'''tests for MAV_CMD_NAV_SET_YAW_SPEED guided-mode command'''6425self.change_mode('GUIDED')6426self.wait_ready_to_arm()6427self.arm_vehicle()64286429for method in self.run_cmd, self.run_cmd_int:6430self.change_mode('MANUAL')6431self.wait_groundspeed(0, 1)6432self.change_mode('GUIDED')6433self.start_subtest("Absolute angles")6434for (heading, speed) in (10, 5), (190, 10), (0, 2), (135, 6):6435def cf(*args, **kwargs):6436method(6437mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,6438p1=heading,6439p2=speed,6440p3=0, # zero is absolute-angles6441)6442self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2)6443self.wait_heading(heading-0.5, heading+0.5, called_function=cf, minimum_duration=2)64446445self.start_subtest("relative angles")6446original_angle = 906447method(6448mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,6449p1=original_angle,6450p2=5,6451p3=0, # zero is absolute-angles6452)6453self.wait_groundspeed(4, 6)6454self.wait_heading(original_angle-0.5, original_angle+0.5)64556456expected_angle = original_angle6457for (angle_delta, speed) in (5, 6), (-30, 2), (180, 7):6458method(6459mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,6460p1=angle_delta,6461p2=speed,6462p3=1, # one is relative-angles6463)64646465def cf(*args, **kwargs):6466method(6467mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,6468p1=0,6469p2=speed,6470p3=1, # one is absolute-angles6471)6472expected_angle += angle_delta6473if expected_angle < 0:6474expected_angle += 3606475if expected_angle > 360:6476expected_angle -= 3606477self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2)6478self.wait_heading(expected_angle, called_function=cf, minimum_duration=2)6479self.do_RTL()6480self.disarm_vehicle()64816482def _MAV_CMD_GET_HOME_POSITION(self, run_cmd):6483'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''6484self.context_collect('HOME_POSITION')6485run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION)6486self.assert_receive_message('HOME_POSITION', check_context=True)64876488def MAV_CMD_GET_HOME_POSITION(self):6489'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''6490self.change_mode('LOITER')6491self.wait_ready_to_arm()6492self._MAV_CMD_GET_HOME_POSITION(self.run_cmd)6493self._MAV_CMD_GET_HOME_POSITION(self.run_cmd_int)64946495def MAV_CMD_DO_FENCE_ENABLE(self):6496'''ensure MAV_CMD_DO_FENCE_ENABLE mavlink command works'''6497here = self.mav.location()64986499self.upload_fences_from_locations([6500(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [6501# east6502self.offset_location_ne(here, -50, 20), # bl6503self.offset_location_ne(here, 50, 20), # br6504self.offset_location_ne(here, 50, 40), # tr6505self.offset_location_ne(here, -50, 40), # tl,6506]),6507(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [6508# over the top of the vehicle6509self.offset_location_ne(here, -50, -50), # bl6510self.offset_location_ne(here, -50, 50), # br6511self.offset_location_ne(here, 50, 50), # tr6512self.offset_location_ne(here, 50, -50), # tl,6513]),6514])65156516# enable:6517self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1)6518self.assert_fence_enabled()65196520# disable6521self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0)6522self.assert_fence_disabled()65236524def MAV_CMD_BATTERY_RESET(self):6525'''manipulate battery levels with MAV_CMD_BATTERY_RESET'''6526for (run_cmd, value) in (self.run_cmd, 56), (self.run_cmd_int, 97):6527run_cmd(6528mavutil.mavlink.MAV_CMD_BATTERY_RESET,6529p1=65535, # battery mask6530p2=value,6531)6532self.assert_received_message_field_values('BATTERY_STATUS', {6533"battery_remaining": value,6534}, {6535"poll": True,6536})65376538def TestWebServer(self, url):6539'''test active web server'''6540self.progress("Accessing webserver main page")6541import urllib.request65426543main_page = urllib.request.urlopen(url).read().decode('utf-8')6544if main_page.find('ArduPilot Web Server') == -1:6545raise NotAchievedException("Expected banner on main page")65466547board_status = urllib.request.urlopen(url + '/@DYNAMIC/board_status.shtml').read().decode('utf-8')6548if board_status.find('0 hours') == -1:6549raise NotAchievedException("Expected uptime in board status")6550if board_status.find('40.713') == -1:6551raise NotAchievedException("Expected lattitude in board status")65526553self.progress("WebServer tests OK")65546555def NetworkingWebServer(self):6556'''web server'''6557applet_script = "net_webserver.lua"65586559self.context_push()6560self.install_applet_script_context(applet_script)65616562self.set_parameters({6563"SCR_ENABLE": 1,6564"SCR_VM_I_COUNT": 1000000,6565"SIM_SPEEDUP": 20,6566"NET_ENABLE": 1,6567})65686569self.reboot_sitl()65706571self.context_push()6572self.context_collect('STATUSTEXT')65736574self.set_parameters({6575"WEB_BIND_PORT": 8081,6576})65776578self.scripting_restart()6579self.wait_text("WebServer: starting on port 8081", check_context=True)65806581self.wait_ready_to_arm()65826583self.TestWebServer("http://127.0.0.1:8081")65846585self.context_pop()6586self.context_pop()6587self.reboot_sitl()65886589def NetworkingWebServerPPP(self):6590'''web server over PPP'''6591applet_script = "net_webserver.lua"65926593self.context_push()6594self.install_applet_script_context(applet_script)65956596self.set_parameters({6597"SCR_ENABLE": 1,6598"SCR_VM_I_COUNT": 1000000,6599"SIM_SPEEDUP": 20,6600"NET_ENABLE": 1,6601"SERIAL5_PROTOCOL": 48,6602})66036604self.progress('rebuilding rover with ppp enabled')6605import shutil6606shutil.copy('build/sitl/bin/ardurover', 'build/sitl/bin/ardurover.noppp')6607util.build_SITL('bin/ardurover', clean=False, configure=True, extra_configure_args=['--enable-PPP', '--debug'])66086609self.reboot_sitl()66106611self.progress("Starting PPP daemon")6612pppd = util.start_PPP_daemon("192.168.14.15:192.168.14.13", '127.0.0.1:5765')66136614self.context_push()6615self.context_collect('STATUSTEXT')66166617pppd.expect("remote IP address 192.168.14.13")66186619self.progress("PPP daemon started")66206621self.set_parameters({6622"WEB_BIND_PORT": 8081,6623})66246625self.scripting_restart()6626self.wait_text("WebServer: starting on port 8081", check_context=True)66276628self.wait_ready_to_arm()66296630self.TestWebServer("http://192.168.14.13:8081")66316632self.context_pop()6633self.context_pop()66346635# restore rover without ppp enabled for next test6636os.unlink('build/sitl/bin/ardurover')6637shutil.copy('build/sitl/bin/ardurover.noppp', 'build/sitl/bin/ardurover')6638self.reboot_sitl()66396640def FenceFullAndPartialTransfer(self, target_system=1, target_component=1):6641'''ensure starting a fence transfer then a partial transfer behaves6642appropriately'''6643# start uploading a 10 item list:6644self.mav.mav.mission_count_send(6645target_system,6646target_component,664710,6648mavutil.mavlink.MAV_MISSION_TYPE_FENCE6649)6650self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)6651# change our mind and try a partial mission upload:6652self.mav.mav.mission_write_partial_list_send(6653target_system,6654target_component,66553,66563,6657mavutil.mavlink.MAV_MISSION_TYPE_FENCE)6658# should get denied for that one:6659self.assert_receive_mission_ack(6660mavutil.mavlink.MAV_MISSION_TYPE_FENCE,6661want_type=mavutil.mavlink.MAV_MISSION_DENIED,6662)6663# now wait for the original upload to be "cancelled"6664self.assert_receive_mission_ack(6665mavutil.mavlink.MAV_MISSION_TYPE_FENCE,6666want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED,6667)66686669def MissionRetransfer(self, target_system=1, target_component=1):6670'''torture-test with MISSION_COUNT'''6671# self.send_debug_trap()6672self.mav.mav.mission_count_send(6673target_system,6674target_component,667510,6676mavutil.mavlink.MAV_MISSION_TYPE_FENCE6677)6678self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)6679self.context_push()6680self.context_collect('STATUSTEXT')6681self.mav.mav.mission_count_send(6682target_system,6683target_component,668410000,6685mavutil.mavlink.MAV_MISSION_TYPE_FENCE6686)6687self.wait_statustext('Only [0-9]+ items are supported', regex=True, check_context=True)6688self.context_pop()6689self.assert_not_receive_message('MISSION_REQUEST')6690self.mav.mav.mission_count_send(6691target_system,6692target_component,669310,6694mavutil.mavlink.MAV_MISSION_TYPE_FENCE6695)6696self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)6697self.assert_receive_mission_ack(6698mavutil.mavlink.MAV_MISSION_TYPE_FENCE,6699want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED,6700)67016702def MissionPolyEnabledPreArm(self):6703'''check Polygon porearm checks'''6704self.set_parameters({6705'FENCE_ENABLE': 1,6706})6707self.progress("Ensure that we can arm if polyfence is enabled but we have no polyfence")6708self.assert_parameter_value('FENCE_TYPE', 6)6709self.wait_ready_to_arm()6710self.reboot_sitl()6711self.wait_ready_to_arm()67126713self.progress("Ensure we can arm when we have an inclusion fence we are inside of")6714here = self.mav.location()6715self.upload_fences_from_locations([6716(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [6717# over the top of the vehicle6718self.offset_location_ne(here, -50, -50), # bl6719self.offset_location_ne(here, -50, 50), # br6720self.offset_location_ne(here, 50, 50), # tr6721self.offset_location_ne(here, 50, -50), # tl,6722]),6723])6724self.delay_sim_time(5)6725self.wait_ready_to_arm()67266727self.reboot_sitl()6728self.wait_ready_to_arm()67296730self.progress("Ensure we can't arm when we are in breacnh of a polyfence")6731self.clear_fence()67326733self.progress("Now create a fence we are in breach of")6734here = self.mav.location()6735self.upload_fences_from_locations([6736(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [6737# over the top of the vehicle6738self.offset_location_ne(here, 20, 20), # bl6739self.offset_location_ne(here, 20, 50), # br6740self.offset_location_ne(here, 50, 50), # tr6741self.offset_location_ne(here, 50, 20), # tl,6742]),6743])67446745self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False)6746self.reboot_sitl()67476748self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)67496750self.progress("Ensure we can arm when a polyfence fence is cleared when we've previously been in breach")6751self.clear_fence()6752self.wait_ready_to_arm()67536754self.upload_fences_from_locations([6755(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [6756# over the top of the vehicle6757self.offset_location_ne(here, 20, 20), # bl6758self.offset_location_ne(here, 20, 50), # br6759self.offset_location_ne(here, 50, 50), # tr6760self.offset_location_ne(here, 50, 20), # tl,6761]),6762])6763self.reboot_sitl()6764self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)6765self.clear_fence()6766self.wait_ready_to_arm()67676768self.progress("Ensure we can arm after clearing polygon fence type enabled")6769self.upload_fences_from_locations([6770(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [6771# over the top of the vehicle6772self.offset_location_ne(here, 20, 20), # bl6773self.offset_location_ne(here, 20, 50), # br6774self.offset_location_ne(here, 50, 50), # tr6775self.offset_location_ne(here, 50, 20), # tl,6776]),6777])6778self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)6779self.set_parameter('FENCE_TYPE', 2)6780self.wait_ready_to_arm()6781self.set_parameter('FENCE_TYPE', 6)6782self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)67836784def OpticalFlow(self):6785'''lightly test OpticalFlow'''6786self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, False, False, False, verbose=True)67876788self.context_push()6789self.set_parameter("SIM_FLOW_ENABLE", 1)6790self.set_parameter("FLOW_TYPE", 10)67916792self.reboot_sitl()6793self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, True, True, True, verbose=True)67946795self.context_pop()6796self.reboot_sitl()67976798def RCDuplicateOptionsExist(self):6799'''ensure duplicate RC option detection works'''6800self.wait_ready_to_arm()6801self.set_parameters({6802"RC6_OPTION": 118,6803"RC7_OPTION": 118,6804})6805self.assert_arm_failure("Duplicate Aux Switch Options")68066807def JammingSimulation(self):6808'''Test jamming simulation works'''6809self.wait_ready_to_arm()6810start_loc = self.assert_receive_message('GPS_RAW_INT')6811self.set_parameter("SIM_GPS1_JAM", 1)68126813class Requirement():6814def __init__(self, field, min_value):6815self.field = field6816self.min_value = min_value68176818def met(self, m):6819return getattr(m, self.field) > self.min_value68206821requirements = set([6822Requirement('v_acc', 50000),6823Requirement('h_acc', 50000),6824Requirement('vel_acc', 1000),6825Requirement('vel', 10000),6826])6827low_sats_seen = False6828seen_bad_loc = False6829tstart = self.get_sim_time()68306831while True:6832if self.get_sim_time() - tstart > 120:6833raise NotAchievedException("Did not see all jamming")6834m = self.assert_receive_message('GPS_RAW_INT')6835new_requirements = copy.copy(requirements)6836for requirement in requirements:6837if requirement.met(m):6838new_requirements.remove(requirement)6839requirements = new_requirements6840if m.satellites_visible < 6:6841low_sats_seen = True6842here = self.assert_receive_message('GPS_RAW_INT')6843if self.get_distance_int(start_loc, here) > 100:6844seen_bad_loc = True68456846if len(requirements) == 0 and low_sats_seen and seen_bad_loc:6847break68486849def BatteryInvalid(self):6850'''check Battery prearms report useful data to user'''6851self.start_subtest("Changing battery types makes no difference")6852self.set_parameter("BATT_MONITOR", 0)6853self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)6854self.set_parameter("BATT_MONITOR", 4)6855self.wait_ready_to_arm()68566857self.start_subtest("No battery monitor should be armable")6858self.set_parameter("BATT_MONITOR", 0)6859self.reboot_sitl()6860self.wait_ready_to_arm()68616862self.set_parameter("BATT_MONITOR", 4)6863self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)6864self.reboot_sitl()6865self.wait_ready_to_arm()68666867self.start_subtest("Invalid backend should have a clear error")6868self.set_parameter("BATT_MONITOR", 98)6869self.reboot_sitl()6870self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)68716872self.start_subtest("Switching from an invalid backend to a valid backend should require a reboot")6873self.set_parameter("BATT_MONITOR", 4)6874self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)68756876self.start_subtest("Switching to None should NOT require a reboot")6877self.set_parameter("BATT_MONITOR", 0)6878self.wait_ready_to_arm()68796880# this method modified from cmd_addpoly in the MAVProxy code:6881def generate_polyfence(self, centre_loc, command, radius, count, rotation=0):6882'''adds a number of waypoints equally spaced around a circle68836884'''6885if count < 3:6886raise ValueError("Invalid count (%s)" % str(count))6887if radius <= 0:6888raise ValueError("Invalid radius (%s)" % str(radius))68896890latlon = (centre_loc.lat, centre_loc.lng)68916892items = []6893for i in range(0, count):6894(lat, lon) = mavextra.gps_newpos(latlon[0],6895latlon[1],6896360/float(count)*i + rotation,6897radius)68986899m = mavutil.mavlink.MAVLink_mission_item_int_message(69001, # target system69011, # target component69020, # seq6903mavutil.mavlink.MAV_FRAME_GLOBAL, # frame6904command, # command69050, # current69060, # autocontinue6907count, # param1,69080.0, # param2,69090.0, # param369100.0, # param46911int(lat*1e7), # x (latitude)6912int(lon*1e7), # y (longitude)69130, # z (altitude)6914mavutil.mavlink.MAV_MISSION_TYPE_FENCE,6915)6916items.append(m)69176918return items69196920def SDPolyFence(self):6921'''test storage of fence on SD card'''6922self.set_parameters({6923'BRD_SD_FENCE': 32767,6924})6925self.reboot_sitl()69266927home = self.home_position_as_mav_location()6928fence = self.generate_polyfence(6929home,6930mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,6931radius=100,6932count=100,6933)69346935for bearing in range(0, 359, 60):6936x = self.offset_location_heading_distance(home, bearing, 100)6937fence.extend(self.generate_polyfence(6938x,6939mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,6940radius=100,6941count=100,6942))69436944self.correct_wp_seq_numbers(fence)6945self.check_fence_upload_download(fence)69466947self.delay_sim_time(1000)69486949def tests(self):6950'''return list of all tests'''6951ret = super(AutoTestRover, self).tests()69526953ret.extend([6954self.MAVProxy_SetModeUsingSwitch,6955self.HIGH_LATENCY2,6956self.MAVProxy_SetModeUsingMode,6957self.ModeSwitch,6958self.AuxModeSwitch,6959self.DriveRTL,6960self.SmartRTL,6961self.DriveSquare,6962self.DriveMission,6963# self.DriveBrake, # disabled due to frequent failures6964self.MAV_CMD_DO_SEND_BANNER,6965self.DO_SET_MODE,6966self.MAVProxy_DO_SET_MODE,6967self.ServoRelayEvents,6968self.RCOverrides,6969self.RCOverridesCancel,6970self.MANUAL_CONTROL,6971self.Sprayer,6972self.AC_Avoidance,6973self.CameraMission,6974self.Gripper,6975self.GripperMission,6976self.SET_MESSAGE_INTERVAL,6977self.MESSAGE_INTERVAL_COMMAND_INT,6978self.REQUEST_MESSAGE,6979self.SYSID_ENFORCE,6980self.SET_ATTITUDE_TARGET,6981self.SET_ATTITUDE_TARGET_heading,6982self.SET_POSITION_TARGET_LOCAL_NED,6983self.MAV_CMD_DO_SET_MISSION_CURRENT,6984self.MAV_CMD_DO_CHANGE_SPEED,6985self.MAV_CMD_MISSION_START,6986self.MAV_CMD_NAV_SET_YAW_SPEED,6987self.Button,6988self.Rally,6989self.Offboard,6990self.MAVProxyParam,6991self.GCSFence,6992self.GCSMission,6993self.GCSRally,6994self.MotorTest,6995self.WheelEncoders,6996self.DataFlashOverMAVLink,6997self.DataFlash,6998self.SkidSteer,6999self.PolyFence,7000self.SDPolyFence,7001self.PolyFenceAvoidance,7002self.PolyFenceObjectAvoidanceAuto,7003self.PolyFenceObjectAvoidanceGuided,7004self.PolyFenceObjectAvoidanceBendyRuler,7005self.SendToComponents,7006self.PolyFenceObjectAvoidanceBendyRulerEasierGuided,7007self.PolyFenceObjectAvoidanceBendyRulerEasierAuto,7008self.SlewRate,7009self.Scripting,7010self.ScriptingSteeringAndThrottle,7011self.MissionFrames,7012self.SetpointGlobalPos,7013self.SetpointGlobalVel,7014self.AccelCal,7015self.RangeFinder,7016self.AP_Proximity_MAV,7017self.EndMissionBehavior,7018self.FlashStorage,7019self.FRAMStorage,7020self.DepthFinder,7021self.ChangeModeByNumber,7022self.EStopAtBoot,7023self.MAV_CMD_NAV_RETURN_TO_LAUNCH,7024self.StickMixingAuto,7025self.AutoDock,7026self.PrivateChannel,7027self.GCSFailsafe,7028self.RoverInitialMode,7029self.DriveMaxRCIN,7030self.NoArmWithoutMissionItems,7031self.CompassPrearms,7032self.MAV_CMD_DO_SET_REVERSE,7033self.MAV_CMD_GET_HOME_POSITION,7034self.MAV_CMD_DO_FENCE_ENABLE,7035self.MAV_CMD_BATTERY_RESET,7036self.NetworkingWebServer,7037self.NetworkingWebServerPPP,7038self.RTL_SPEED,7039self.MissionRetransfer,7040self.FenceFullAndPartialTransfer,7041self.MissionPolyEnabledPreArm,7042self.OpticalFlow,7043self.RCDuplicateOptionsExist,7044self.ClearMission,7045self.JammingSimulation,7046self.BatteryInvalid,7047])7048return ret70497050def disabled_tests(self):7051return {7052"SlewRate": "got timing report failure on CI",7053"MAV_CMD_NAV_SET_YAW_SPEED": "compiled out of code by default",7054"PolyFenceObjectAvoidanceBendyRuler": "unreliable",7055}70567057def rc_defaults(self):7058ret = super(AutoTestRover, self).rc_defaults()7059ret[3] = 15007060ret[8] = 18007061return ret70627063def initial_mode_switch_mode(self):7064return "MANUAL"70657066def default_mode(self):7067return 'MANUAL'706870697070