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/blimp.py
Views: 1798
'''1Fly Blimp in SITL23AP_FLAKE8_CLEAN4'''56from __future__ import print_function7import os8import shutil910from pymavlink import mavutil1112from vehicle_test_suite import TestSuite1314# get location of scripts15testdir = os.path.dirname(os.path.realpath(__file__))16SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 0)1718# Flight mode switch positions are set-up in blimp.parm to be19# switch 1 = Land20# switch 2 = Manual21# switch 3 = Velocity22# switch 4 = Loiter23# switch 5 = Manual24# switch 6 = Manual252627class AutoTestBlimp(TestSuite):28@staticmethod29def get_not_armable_mode_list():30return []3132@staticmethod33def get_not_disarmed_settable_modes_list():34return []3536@staticmethod37def get_no_position_not_settable_modes_list():38return []3940@staticmethod41def get_position_armable_modes_list():42return []4344@staticmethod45def get_normal_armable_modes_list():46return []4748def log_name(self):49return "Blimp"5051def default_mode(self):52return "MANUAL"5354def test_filepath(self):55return os.path.realpath(__file__)5657def default_speedup(self):58return 1005960def set_current_test_name(self, name):61self.current_test_name_directory = "Blimp_Tests/" + name + "/"6263def sitl_start_location(self):64return SITL_START_LOCATION6566def sitl_streamrate(self):67return 56869def vehicleinfo_key(self):70return 'Blimp'7172def default_frame(self):73return "Blimp"7475def apply_defaultfile_parameters(self):76# Blimp passes in a defaults_filepath in place of applying77# parameters afterwards.78pass7980def defaults_filepath(self):81return self.model_defaults_filepath(self.frame)8283def wait_disarmed_default_wait_time(self):84return 1208586def close(self):87super(AutoTestBlimp, self).close()8889# [2014/05/07] FC Because I'm doing a cross machine build90# (source is on host, build is on guest VM) I cannot hard link91# This flag tells me that I need to copy the data out92if self.copy_tlog:93shutil.copy(self.logfile, self.buildlog)9495def is_blimp(self):96return True9798def get_stick_arming_channel(self):99return int(self.get_parameter("RCMAP_YAW"))100101def get_disarm_delay(self):102return int(self.get_parameter("DISARM_DELAY"))103104def set_autodisarm_delay(self, delay):105self.set_parameter("DISARM_DELAY", delay)106107def FlyManual(self):108'''test manual mode'''109self.change_mode('MANUAL')110self.wait_ready_to_arm()111self.arm_vehicle()112113acc = 0.5114115# make sure we don't drift:116bl = self.mav.location()117tl = self.offset_location_ne(location=bl, metres_north=2, metres_east=0)118ttl = self.offset_location_ne(location=bl, metres_north=4, metres_east=0)119tr = self.offset_location_ne(location=bl, metres_north=4, metres_east=2)120ttr = self.offset_location_ne(location=bl, metres_north=4, metres_east=4)121122if self.mavproxy is not None:123self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")124self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")125self.mavproxy.send(f"map icon {ttl.lat} {ttl.lng} flag\n")126self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")127self.mavproxy.send(f"map icon {ttr.lat} {ttr.lng} flag\n")128129self.set_rc(2, 2000)130self.wait_distance_to_location(tl, 0, acc, timeout=10)131self.set_rc(2, 1500)132self.wait_distance_to_location(ttl, 0, acc, timeout=15)133self.set_rc(1, 2000)134self.wait_distance_to_location(tr, 0, acc, timeout=10)135self.set_rc(1, 1500)136self.wait_distance_to_location(ttr, 0, acc, timeout=15)137self.change_mode('RTL')138self.wait_distance_to_location(bl, 0, 0.5, timeout=30, minimum_duration=5) # make sure it can hold position139self.change_mode('MANUAL')140141self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot142143self.set_rc(3, 2000)144self.wait_altitude(5, 5.5, relative=True, timeout=15)145self.set_rc(3, 1500)146147self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot148149self.set_rc(4, 1000)150self.wait_heading(340, accuracy=5, timeout=5) # short timeout to check yawrate151self.set_rc(4, 1500)152153self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot154155self.set_rc(3, 1000)156self.wait_altitude(0, 0.5, relative=True, timeout=20)157self.set_rc(3, 1500)158159self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot160161self.set_rc(4, 2000)162self.wait_heading(135, accuracy=5, timeout=10) # short timeout to check yawrate163self.set_rc(4, 1500)164165self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot166167self.disarm_vehicle()168169def FlyLoiter(self):170'''test loiter mode'''171172self.change_mode('LOITER')173self.wait_ready_to_arm()174self.arm_vehicle()175176siz = 5177tim = 60178179# make sure we don't drift:180bl = self.mav.location()181tl = self.offset_location_ne(location=bl, metres_north=siz, metres_east=0)182tr = self.offset_location_ne(location=bl, metres_north=siz, metres_east=siz)183br = self.offset_location_ne(location=bl, metres_north=0, metres_east=siz)184185print("Locations are:")186print("bottom left ", bl.lat, bl.lng)187print("top left ", tl.lat, tl.lng)188print("top right ", tr.lat, tr.lng)189print("bottom right ", br.lat, br.lng)190191if self.mavproxy is not None:192self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n")193self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n")194self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n")195self.mavproxy.send(f"map icon {br.lat} {br.lng} flag\n")196197self.set_parameter("SIMPLE_MODE", 1)198199self.set_rc(2, 2000)200self.wait_distance_to_location(tl, 0, 0.2, timeout=tim)201self.set_rc(2, 1500)202203self.set_rc(1, 2000)204self.wait_distance_to_location(tr, 0, 0.5, timeout=tim)205self.set_rc(1, 1500)206207self.set_rc(2, 1000)208self.wait_distance_to_location(br, 0, 0.5, timeout=tim)209self.set_rc(2, 1500)210211self.set_rc(1, 1000)212self.wait_distance_to_location(bl, 0, 0.5, timeout=tim)213self.set_rc(1, 1500)214215fin = self.mav.location()216217self.set_rc(4, 1700)218self.wait_heading(135, accuracy=2, timeout=tim)219self.set_rc(4, 1500)220221self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot222223self.set_rc(3, 2000)224self.wait_altitude(5, 5.5, relative=True, timeout=60)225self.set_rc(3, 1000)226self.wait_altitude(0, 0.5, relative=True, timeout=60)227self.set_rc(3, 1500)228229self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot230231self.set_rc(4, 1300)232self.wait_heading(0, accuracy=2, timeout=tim)233self.set_rc(4, 1500)234235self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot236237self.disarm_vehicle()238239def PREFLIGHT_Pressure(self):240'''test triggering pressure calibration with mavlink command'''241# as airspeed is not instantiated on Blimp we expect to242# instantly get back an accepted.243self.run_cmd(244mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,245p3=1, # p3, baro246)247248def tests(self):249'''return list of all tests'''250# ret = super(AutoTestBlimp, self).tests()251ret = []252ret.extend([253self.FlyManual,254self.FlyLoiter,255self.PREFLIGHT_Pressure,256])257return ret258259def disabled_tests(self):260return {261}262263264