CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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