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/antennatracker.py
Views: 1798
'''1Test AntennaTracker vehicle in SITL23AP_FLAKE8_CLEAN45'''67from __future__ import print_function89import math10import operator11import os1213from pymavlink import mavextra14from pymavlink import mavutil1516import vehicle_test_suite17from vehicle_test_suite import NotAchievedException1819# get location of scripts20testdir = os.path.dirname(os.path.realpath(__file__))21SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)222324class AutoTestTracker(vehicle_test_suite.TestSuite):2526def log_name(self):27return "AntennaTracker"2829def default_speedup(self):30'''Tracker seems to be race-free'''31return 1003233def test_filepath(self):34return os.path.realpath(__file__)3536def sitl_start_location(self):37return SITL_START_LOCATION3839def default_mode(self):40return "AUTO"4142def is_tracker(self):43return True4445def default_frame(self):46return "tracker"4748def set_current_test_name(self, name):49self.current_test_name_directory = "AntennaTracker_Tests/" + name + "/"5051def apply_defaultfile_parameters(self):52# tracker doesn't have a default parameters file53pass5455def sysid_thismav(self):56return 25758def achieve_attitude(self, desyaw, despitch, tolerance=1, target_system=2, target_component=1):59'''use set_attitude_target to achieve desyaw / despitch'''60tstart = self.get_sim_time()61last_attitude_target_sent = 062last_debug = 063self.progress("Using set_attitude_target to achieve attitude")64while True:65now = self.get_sim_time()66if now - tstart > 60:67raise NotAchievedException("Did not achieve attitude")68if now - last_attitude_target_sent > 0.5:69last_attitude_target_sent = now70type_mask = (711 << 0 | # ignore roll rate721 << 6 # ignore throttle73)74self.mav.mav.set_attitude_target_send(750, # time_boot_ms76target_system, # target sysid77target_component, # target compid78type_mask, # bitmask of things to ignore79mavextra.euler_to_quat([0,80math.radians(despitch),81math.radians(desyaw)]), # att820, # yaw rate (rad/s)830, # pitch rate840, # yaw rate850) # thrust, 0 to 1, translated to a climb/descent rate86m = self.assert_receive_message('ATTITUDE', timeout=2)87if now - last_debug > 1:88last_debug = now89self.progress("yaw=%f desyaw=%f pitch=%f despitch=%f" %90(math.degrees(m.yaw), desyaw,91math.degrees(m.pitch), despitch))92yaw_ok = abs(math.degrees(m.yaw) - desyaw) < tolerance93pitch_ok = abs(math.degrees(m.pitch) - despitch) < tolerance94if yaw_ok and pitch_ok:95self.progress("Achieved attitude")96break9798def reboot_sitl(self, *args, **kwargs):99self.disarm_vehicle()100super(AutoTestTracker, self).reboot_sitl(*args, **kwargs)101102def GUIDED(self):103'''Test GUIDED mode'''104self.reboot_sitl() # temporary hack around control issues105self.change_mode(4) # "GUIDED"106self.achieve_attitude(desyaw=10, despitch=30)107self.achieve_attitude(desyaw=0, despitch=0)108self.achieve_attitude(desyaw=45, despitch=10)109110def MANUAL(self):111'''Test MANUAL mode'''112self.change_mode(0) # "MANUAL"113for chan in 1, 2:114for pwm in 1200, 1600, 1367:115self.set_rc(chan, pwm)116self.wait_servo_channel_value(chan, pwm)117118def MAV_CMD_DO_SET_SERVO(self):119'''Test SERVOTEST mode'''120self.change_mode(0) # "MANUAL"121# magically changes to SERVOTEST (3)122for method in self.run_cmd, self.run_cmd_int:123for value in 1900, 1200:124channel = 1125method(126mavutil.mavlink.MAV_CMD_DO_SET_SERVO,127p1=channel,128p2=value,129timeout=1,130)131self.wait_servo_channel_value(channel, value)132for value in 1300, 1670:133channel = 2134method(135mavutil.mavlink.MAV_CMD_DO_SET_SERVO,136p1=channel,137p2=value,138timeout=1,139)140self.wait_servo_channel_value(channel, value)141142def MAV_CMD_MISSION_START(self):143'''test MAV_CMD_MISSION_START mavlink command'''144for method in self.run_cmd, self.run_cmd_int:145self.change_mode(0) # "MANUAL"146method(mavutil.mavlink.MAV_CMD_MISSION_START)147self.wait_mode("AUTO")148149def SCAN(self):150'''Test SCAN mode'''151self.change_mode(2) # "SCAN"152self.set_parameter("SCAN_SPEED_YAW", 20)153for channel in 1, 2:154self.wait_servo_channel_value(channel,1551900,156timeout=90,157comparator=operator.ge)158for channel in 1, 2:159self.wait_servo_channel_value(channel,1601200,161timeout=90,162comparator=operator.le)163164def BaseMessageSet(self):165'''ensure we're getting messages we expect'''166self.set_parameter('BATT_MONITOR', 4)167self.reboot_sitl()168for msg in 'BATTERY_STATUS', :169self.assert_receive_message(msg)170171def disabled_tests(self):172return {173"ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652",174"CPUFailsafe": " tracker doesn't have a CPU failsafe",175}176177def GPSForYaw(self):178'''Moving baseline GPS yaw'''179self.load_default_params_file("tracker-gps-for-yaw.parm")180self.reboot_sitl()181182self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)183tstart = self.get_sim_time()184while True:185if self.get_sim_time_cached() - tstart > 20:186break187m_gps_raw = self.assert_receive_message("GPS2_RAW", verbose=True)188m_sim = self.assert_receive_message("SIMSTATE", verbose=True)189gps_raw_hdg = m_gps_raw.yaw * 0.01190sim_hdg = mavextra.wrap_360(math.degrees(m_sim.yaw))191if abs(gps_raw_hdg - sim_hdg) > 5:192raise NotAchievedException("GPS_RAW not tracking simstate yaw")193self.progress(f"yaw match ({gps_raw_hdg} vs {sim_hdg}")194195def tests(self):196'''return list of all tests'''197ret = super(AutoTestTracker, self).tests()198ret.extend([199self.GUIDED,200self.MANUAL,201self.MAV_CMD_DO_SET_SERVO,202self.MAV_CMD_MISSION_START,203self.NMEAOutput,204self.SCAN,205self.BaseMessageSet,206self.GPSForYaw,207])208return ret209210211