Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/antennatracker.py
9770 views
1
'''
2
Test AntennaTracker vehicle in SITL
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
import math
9
import operator
10
import os
11
12
from pymavlink import mavextra
13
from pymavlink import mavutil
14
15
import vehicle_test_suite
16
from vehicle_test_suite import NotAchievedException
17
18
# get location of scripts
19
testdir = os.path.dirname(os.path.realpath(__file__))
20
SITL_START_LOCATION = mavutil.location(-27.274439, 151.290064, 343, 8.7)
21
22
23
class AutoTestTracker(vehicle_test_suite.TestSuite):
24
25
def log_name(self):
26
return "AntennaTracker"
27
28
def default_speedup(self):
29
'''Tracker seems to be race-free'''
30
return 100
31
32
def test_filepath(self):
33
return os.path.realpath(__file__)
34
35
def sitl_start_location(self):
36
return SITL_START_LOCATION
37
38
def default_mode(self):
39
return "AUTO"
40
41
def is_tracker(self):
42
return True
43
44
def default_frame(self):
45
return "tracker"
46
47
def set_current_test_name(self, name):
48
self.current_test_name_directory = "AntennaTracker_Tests/" + name + "/"
49
50
def apply_defaultfile_parameters(self):
51
# tracker doesn't have a default parameters file
52
pass
53
54
def sysid_thismav(self):
55
return 2
56
57
def achieve_attitude(self, desyaw, despitch, tolerance=1, target_system=2, target_component=1):
58
'''use set_attitude_target to achieve desyaw / despitch'''
59
tstart = self.get_sim_time()
60
last_attitude_target_sent = 0
61
last_debug = 0
62
self.progress("Using set_attitude_target to achieve attitude")
63
while True:
64
now = self.get_sim_time()
65
if now - tstart > 60:
66
raise NotAchievedException("Did not achieve attitude")
67
if now - last_attitude_target_sent > 0.5:
68
last_attitude_target_sent = now
69
type_mask = (
70
1 << 0 | # ignore roll rate
71
1 << 6 # ignore throttle
72
)
73
self.mav.mav.set_attitude_target_send(
74
0, # time_boot_ms
75
target_system, # target sysid
76
target_component, # target compid
77
type_mask, # bitmask of things to ignore
78
mavextra.euler_to_quat([0,
79
math.radians(despitch),
80
math.radians(desyaw)]), # att
81
0, # yaw rate (rad/s)
82
0, # pitch rate
83
0, # yaw rate
84
0) # thrust, 0 to 1, translated to a climb/descent rate
85
m = self.assert_receive_message('ATTITUDE', timeout=2)
86
if now - last_debug > 1:
87
last_debug = now
88
self.progress("yaw=%f desyaw=%f pitch=%f despitch=%f" %
89
(math.degrees(m.yaw), desyaw,
90
math.degrees(m.pitch), despitch))
91
yaw_ok = abs(math.degrees(m.yaw) - desyaw) < tolerance
92
pitch_ok = abs(math.degrees(m.pitch) - despitch) < tolerance
93
if yaw_ok and pitch_ok:
94
self.progress("Achieved attitude")
95
break
96
97
def reboot_sitl(self, *args, **kwargs):
98
self.disarm_vehicle()
99
super(AutoTestTracker, self).reboot_sitl(*args, **kwargs)
100
101
def GUIDED(self):
102
'''Test GUIDED mode'''
103
self.reboot_sitl() # temporary hack around control issues
104
self.change_mode(4) # "GUIDED"
105
self.achieve_attitude(desyaw=10, despitch=30)
106
self.achieve_attitude(desyaw=0, despitch=0)
107
self.achieve_attitude(desyaw=45, despitch=10)
108
109
def MANUAL(self):
110
'''Test MANUAL mode'''
111
self.change_mode(0) # "MANUAL"
112
for chan in 1, 2:
113
for pwm in 1200, 1600, 1367:
114
self.set_rc(chan, pwm)
115
self.wait_servo_channel_value(chan, pwm)
116
117
def MAV_CMD_DO_SET_SERVO(self):
118
'''Test SERVOTEST mode'''
119
self.change_mode(0) # "MANUAL"
120
# magically changes to SERVOTEST (3)
121
for method in self.run_cmd, self.run_cmd_int:
122
for value in 1900, 1200:
123
channel = 1
124
method(
125
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
126
p1=channel,
127
p2=value,
128
timeout=1,
129
)
130
self.wait_servo_channel_value(channel, value)
131
for value in 1300, 1670:
132
channel = 2
133
method(
134
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
135
p1=channel,
136
p2=value,
137
timeout=1,
138
)
139
self.wait_servo_channel_value(channel, value)
140
141
def MAV_CMD_MISSION_START(self):
142
'''test MAV_CMD_MISSION_START mavlink command'''
143
for method in self.run_cmd, self.run_cmd_int:
144
self.change_mode(0) # "MANUAL"
145
method(mavutil.mavlink.MAV_CMD_MISSION_START)
146
self.wait_mode("AUTO")
147
148
def SCAN(self):
149
'''Test SCAN mode'''
150
self.change_mode(2) # "SCAN"
151
self.set_parameter("SCAN_SPEED_YAW", 20)
152
for channel in 1, 2:
153
self.wait_servo_channel_value(channel,
154
1900,
155
timeout=90,
156
comparator=operator.ge)
157
for channel in 1, 2:
158
self.wait_servo_channel_value(channel,
159
1200,
160
timeout=90,
161
comparator=operator.le)
162
163
def BaseMessageSet(self):
164
'''ensure we're getting messages we expect'''
165
self.set_parameter('BATT_MONITOR', 4)
166
self.reboot_sitl()
167
for msg in 'BATTERY_STATUS', :
168
self.assert_receive_message(msg)
169
170
def disabled_tests(self):
171
return {
172
"ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652",
173
"CPUFailsafe": " tracker doesn't have a CPU failsafe",
174
}
175
176
def GPSForYaw(self):
177
'''Moving baseline GPS yaw'''
178
self.load_default_params_file("tracker-gps-for-yaw.parm")
179
self.reboot_sitl()
180
181
self.wait_gps_fix_type_gte(6, message_type="GPS2_RAW", verbose=True)
182
tstart = self.get_sim_time()
183
while True:
184
if self.get_sim_time_cached() - tstart > 20:
185
break
186
m_gps_raw = self.assert_receive_message("GPS2_RAW", verbose=True)
187
m_sim = self.assert_receive_message("SIMSTATE", verbose=True)
188
gps_raw_hdg = m_gps_raw.yaw * 0.01
189
sim_hdg = mavextra.wrap_360(math.degrees(m_sim.yaw))
190
if abs(gps_raw_hdg - sim_hdg) > 5:
191
raise NotAchievedException("GPS_RAW not tracking simstate yaw")
192
self.progress(f"yaw match ({gps_raw_hdg} vs {sim_hdg}")
193
194
def LoggerMsgChunks(self):
195
'''create MSG dataflash entries for very long messages'''
196
self.assert_parameter_value('LOG_DISARMED', 1)
197
short_message_text = "This is a short message"
198
long_message_text = "This is undubitably a ridiculously verbose and needlessly wordy missive, unavoidably designed to exceed disappointingly minuscule log buffers" # noqa:E501
199
self.send_statustext(short_message_text)
200
self.send_statustext(long_message_text)
201
202
self.delay_sim_time(10)
203
dfreader = self.dfreader_for_current_onboard_log()
204
self.reboot_sitl()
205
206
phase = "short"
207
seq = 0
208
received_long_message_text = ""
209
while True:
210
m = dfreader.recv_match(type='MSG')
211
if m is None:
212
break
213
self.progress(f"{m.Message=}")
214
msg = m.Message.lstrip("SRC=250/250:")
215
if phase == "short":
216
if msg != short_message_text:
217
continue
218
self.progress("Received short message")
219
phase = "long"
220
elif phase == "long":
221
if m.Seq != seq:
222
received_long_message_text = ""
223
seq = 0
224
if m.Seq != 0:
225
raise NotAchievedException("Weird")
226
else:
227
seq += 1
228
received_long_message_text += msg
229
self.progress(f"Text: {received_long_message_text}")
230
if received_long_message_text == long_message_text:
231
phase = "done"
232
break
233
234
if phase != "done":
235
raise NotAchievedException(f"Did not get message text; {phase=}") # noqa:E501
236
237
def tests(self):
238
'''return list of all tests'''
239
ret = super(AutoTestTracker, self).tests()
240
ret.extend([
241
self.GUIDED,
242
self.MANUAL,
243
self.MAV_CMD_DO_SET_SERVO,
244
self.MAV_CMD_MISSION_START,
245
self.NMEAOutput,
246
self.SCAN,
247
self.BaseMessageSet,
248
self.GPSForYaw,
249
self.LoggerMsgChunks,
250
])
251
return ret
252
253