Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/balancebot.py
9692 views
1
'''
2
Drive a BalanceBot in SITL
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
import os
9
10
from rover import AutoTestRover
11
12
import vehicle_test_suite
13
from vehicle_test_suite import NotAchievedException
14
15
# get location of scripts
16
testdir = os.path.dirname(os.path.realpath(__file__))
17
18
19
class AutoTestBalanceBot(AutoTestRover):
20
21
def log_name(self):
22
return "BalanceBot"
23
24
def vehicleinfo_key(self):
25
return "Rover"
26
27
def init(self):
28
if self.frame is None:
29
self.frame = 'balancebot'
30
super(AutoTestBalanceBot, self).init()
31
32
def DO_SET_MODE(self):
33
'''Set mode via MAV_COMMAND_DO_SET_MODE'''
34
self.do_set_mode_via_command_long("HOLD")
35
self.do_set_mode_via_command_long("MANUAL")
36
37
def rc_defaults(self):
38
ret = super(AutoTestBalanceBot, self).rc_defaults()
39
ret[3] = 1500
40
return ret
41
42
def is_balancebot(self):
43
return True
44
45
def drive_rtl_mission_max_distance_from_home(self):
46
'''maximum distance allowed from home at end'''
47
'''balancebot tends to wander backwards, away from the target'''
48
return 8
49
50
def DriveRTL(self):
51
'''Drive an RTL Mission'''
52
# if we Hold then the balancebot continues to wander
53
# indefinitely at ~1m/s, hence we set to Acro
54
self.set_parameter("MIS_DONE_BEHAVE", 2)
55
super(AutoTestBalanceBot, self).DriveRTL()
56
57
def TestWheelEncoder(self):
58
'''make sure wheel encoders are generally working'''
59
ex = None
60
try:
61
self.set_parameter("WENC_TYPE", 10)
62
self.set_parameter("AHRS_EKF_TYPE", 10)
63
self.reboot_sitl()
64
self.set_parameter("WENC2_TYPE", 10)
65
self.set_parameter("WENC_POS_Y", 0.075)
66
self.set_parameter("WENC2_POS_Y", -0.075)
67
self.reboot_sitl()
68
self.change_mode("HOLD")
69
self.wait_ready_to_arm()
70
self.change_mode("ACRO")
71
self.arm_vehicle()
72
self.set_rc(3, 1600)
73
74
m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5)
75
76
tstart = self.get_sim_time()
77
while True:
78
if self.get_sim_time_cached() - tstart > 10:
79
break
80
dist_home = self.distance_to_home(use_cached_home=True)
81
m = self.mav.messages.get("WHEEL_DISTANCE")
82
delta = abs(m.distance[0] - dist_home)
83
self.progress("dist-home=%f wheel-distance=%f delta=%f" %
84
(dist_home, m.distance[0], delta))
85
if delta > 5:
86
raise NotAchievedException("wheel distance incorrect")
87
self.disarm_vehicle()
88
except Exception as e:
89
self.progress("Caught exception: %s" %
90
self.get_exception_stacktrace(e))
91
self.disarm_vehicle()
92
ex = e
93
self.reboot_sitl()
94
if ex is not None:
95
raise ex
96
97
def DriveMission(self):
98
'''Drive Mission rover1.txt'''
99
self.drive_mission("balancebot1.txt", strict=False)
100
101
def tests(self):
102
'''return list of all tests'''
103
104
'''note that while AutoTestBalanceBot inherits from Rover we don't
105
inherit Rover's tests!'''
106
ret = vehicle_test_suite.TestSuite.tests(self)
107
108
ret.extend([
109
self.DriveRTL,
110
self.DriveMission,
111
self.TestWheelEncoder,
112
self.MAV_CMD_DO_SEND_BANNER,
113
self.DO_SET_MODE,
114
self.ServoRelayEvents,
115
])
116
return ret
117
118
def default_mode(self):
119
return 'MANUAL'
120
121