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/balancebot.py
Views: 1798
'''1Drive a BalanceBot in SITL23AP_FLAKE8_CLEAN45'''67from __future__ import print_function89import os1011from rover import AutoTestRover1213import vehicle_test_suite14from vehicle_test_suite import NotAchievedException1516# get location of scripts17testdir = os.path.dirname(os.path.realpath(__file__))181920class AutoTestBalanceBot(AutoTestRover):2122def log_name(self):23return "BalanceBot"2425def vehicleinfo_key(self):26return "Rover"2728def init(self):29if self.frame is None:30self.frame = 'balancebot'31super(AutoTestBalanceBot, self).init()3233def DO_SET_MODE(self):34'''Set mode via MAV_COMMAND_DO_SET_MODE'''35self.do_set_mode_via_command_long("HOLD")36self.do_set_mode_via_command_long("MANUAL")3738def rc_defaults(self):39ret = super(AutoTestBalanceBot, self).rc_defaults()40ret[3] = 150041return ret4243def is_balancebot(self):44return True4546def drive_rtl_mission_max_distance_from_home(self):47'''maximum distance allowed from home at end'''48'''balancebot tends to wander backwards, away from the target'''49return 85051def DriveRTL(self):52'''Drive an RTL Mission'''53# if we Hold then the balancebot continues to wander54# indefinitely at ~1m/s, hence we set to Acro55self.set_parameter("MIS_DONE_BEHAVE", 2)56super(AutoTestBalanceBot, self).DriveRTL()5758def TestWheelEncoder(self):59'''make sure wheel encoders are generally working'''60ex = None61try:62self.set_parameter("WENC_TYPE", 10)63self.set_parameter("AHRS_EKF_TYPE", 10)64self.reboot_sitl()65self.set_parameter("WENC2_TYPE", 10)66self.set_parameter("WENC_POS_Y", 0.075)67self.set_parameter("WENC2_POS_Y", -0.075)68self.reboot_sitl()69self.change_mode("HOLD")70self.wait_ready_to_arm()71self.change_mode("ACRO")72self.arm_vehicle()73self.set_rc(3, 1600)7475m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5)7677tstart = self.get_sim_time()78while True:79if self.get_sim_time_cached() - tstart > 10:80break81dist_home = self.distance_to_home(use_cached_home=True)82m = self.mav.messages.get("WHEEL_DISTANCE")83delta = abs(m.distance[0] - dist_home)84self.progress("dist-home=%f wheel-distance=%f delta=%f" %85(dist_home, m.distance[0], delta))86if delta > 5:87raise NotAchievedException("wheel distance incorrect")88self.disarm_vehicle()89except Exception as e:90self.progress("Caught exception: %s" %91self.get_exception_stacktrace(e))92self.disarm_vehicle()93ex = e94self.reboot_sitl()95if ex is not None:96raise ex9798def DriveMission(self):99'''Drive Mission rover1.txt'''100self.drive_mission("balancebot1.txt", strict=False)101102def tests(self):103'''return list of all tests'''104105'''note that while AutoTestBalanceBot inherits from Rover we don't106inherit Rover's tests!'''107ret = vehicle_test_suite.TestSuite.tests(self)108109ret.extend([110self.DriveRTL,111self.DriveMission,112self.TestWheelEncoder,113self.MAV_CMD_DO_SEND_BANNER,114self.DO_SET_MODE,115self.ServoRelayEvents,116])117return ret118119def default_mode(self):120return 'MANUAL'121122123