Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/vehicle_test_suite.py
9798 views
1
'''
2
Common base class for each of the autotest suites
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
from __future__ import annotations
9
10
import abc
11
import copy
12
import errno
13
import glob
14
import io
15
import math
16
import os
17
import pathlib
18
import re
19
import shutil
20
import signal
21
import sys
22
import time
23
import traceback
24
from datetime import datetime
25
from typing import List
26
from typing import Tuple
27
from typing import Dict
28
import importlib.util
29
30
import pexpect
31
import fnmatch
32
import operator
33
import numpy
34
import socket
35
import struct
36
import random
37
import tempfile
38
import threading
39
import enum
40
from inspect import currentframe, getframeinfo
41
from pathlib import Path
42
43
from MAVProxy.modules.lib import mp_util
44
from MAVProxy.modules.lib import mp_elevation
45
46
from pymavlink import mavparm
47
from pymavlink import mavwp, mavutil, DFReader
48
from pymavlink import mavextra
49
from pymavlink.rotmat import Vector3
50
from pymavlink import quaternion
51
from pymavlink.generator import mavgen
52
53
from pysim import util, vehicleinfo
54
55
try:
56
import queue as Queue
57
except ImportError:
58
import Queue
59
60
61
# Enumeration convenience class for mavlink POSITION_TARGET_TYPEMASK
62
class MAV_POS_TARGET_TYPE_MASK(enum.IntEnum):
63
POS_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
64
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
65
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE)
66
VEL_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
67
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
68
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE)
69
ACC_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
70
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
71
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE)
72
FORCE_SET = mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET
73
YAW_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE
74
YAW_RATE_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
75
POS_ONLY = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE
76
ALT_ONLY = (VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE |
77
mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
78
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE)
79
IGNORE_ALL = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE | POS_IGNORE
80
LAST_BYTE = 0xF000
81
82
83
MAV_FRAMES_TO_TEST = [
84
mavutil.mavlink.MAV_FRAME_GLOBAL,
85
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
86
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
87
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
88
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
89
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT
90
]
91
92
# get location of scripts
93
testdir = os.path.dirname(os.path.realpath(__file__))
94
95
try:
96
from itertools import izip as zip
97
except ImportError:
98
# probably python2
99
pass
100
101
102
class ErrorException(Exception):
103
"""Base class for other exceptions"""
104
pass
105
106
107
class AutoTestTimeoutException(ErrorException):
108
pass
109
110
111
class WaitModeTimeout(AutoTestTimeoutException):
112
"""Thrown when fails to achieve given mode change."""
113
pass
114
115
116
class WaitAltitudeTimout(AutoTestTimeoutException):
117
"""Thrown when fails to achieve given altitude range."""
118
pass
119
120
121
class WaitGroundSpeedTimeout(AutoTestTimeoutException):
122
"""Thrown when fails to achieve given ground speed range."""
123
pass
124
125
126
class WaitRollTimeout(AutoTestTimeoutException):
127
"""Thrown when fails to achieve given roll in degrees."""
128
pass
129
130
131
class WaitPitchTimeout(AutoTestTimeoutException):
132
"""Thrown when fails to achieve given pitch in degrees."""
133
pass
134
135
136
class WaitHeadingTimeout(AutoTestTimeoutException):
137
"""Thrown when fails to achieve given heading."""
138
pass
139
140
141
class WaitDistanceTimeout(AutoTestTimeoutException):
142
"""Thrown when fails to attain distance"""
143
pass
144
145
146
class WaitLocationTimeout(AutoTestTimeoutException):
147
"""Thrown when fails to attain location"""
148
pass
149
150
151
class WaitWaypointTimeout(AutoTestTimeoutException):
152
"""Thrown when fails to attain waypoint ranges"""
153
pass
154
155
156
class SetRCTimeout(AutoTestTimeoutException):
157
"""Thrown when fails to send RC commands"""
158
pass
159
160
161
class MsgRcvTimeoutException(AutoTestTimeoutException):
162
"""Thrown when fails to receive an expected message"""
163
pass
164
165
166
class NotAchievedException(ErrorException):
167
"""Thrown when fails to achieve a goal"""
168
pass
169
170
171
class OldpymavlinkException(ErrorException):
172
"""Thrown when a new feature is required from pymavlink"""
173
pass
174
175
176
class YawSpeedNotAchievedException(NotAchievedException):
177
"""Thrown when fails to achieve given yaw speed."""
178
pass
179
180
181
class SpeedVectorNotAchievedException(NotAchievedException):
182
"""Thrown when fails to achieve given speed vector."""
183
pass
184
185
186
class PreconditionFailedException(ErrorException):
187
"""Thrown when a precondition for a test is not met"""
188
pass
189
190
191
class ArmedAtEndOfTestException(ErrorException):
192
"""Created when test left vehicle armed"""
193
pass
194
195
196
class Context(object):
197
def __init__(self):
198
self.parameters = []
199
self.sitl_commandline_customised = False
200
self.reboot_sitl_was_done = False
201
self.message_hooks = []
202
self.collections = {}
203
self.heartbeat_interval_ms = 1000
204
self.original_heartbeat_interval_ms = None
205
self.installed_scripts = []
206
self.installed_modules = []
207
self.overridden_message_rates = {}
208
self.raising_debug_trap_on_exceptions = False
209
210
211
# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python
212
class TeeBoth(object):
213
def __init__(self, name, mode, mavproxy_logfile, suppress_stdout=False):
214
self.suppress_stdout = suppress_stdout
215
self.file = open(name, mode)
216
self.stdout = sys.stdout
217
self.stderr = sys.stderr
218
self.mavproxy_logfile = mavproxy_logfile
219
self.mavproxy_logfile.set_fh(self)
220
sys.stdout = self
221
sys.stderr = self
222
223
def close(self):
224
sys.stdout = self.stdout
225
sys.stderr = self.stderr
226
self.mavproxy_logfile.set_fh(None)
227
self.mavproxy_logfile = None
228
self.file.close()
229
self.file = None
230
231
def write(self, data):
232
if isinstance(data, bytes):
233
data = data.decode('ascii')
234
self.file.write(data)
235
if not self.suppress_stdout:
236
self.stdout.write(data)
237
238
def flush(self):
239
self.file.flush()
240
241
242
class MAVProxyLogFile(object):
243
def __init__(self):
244
self.fh = None
245
246
def close(self):
247
pass
248
249
def set_fh(self, fh):
250
self.fh = fh
251
252
def write(self, data):
253
if self.fh is not None:
254
self.fh.write(data)
255
else:
256
sys.stdout.write(data)
257
258
def flush(self):
259
if self.fh is not None:
260
self.fh.flush()
261
else:
262
sys.stdout.flush()
263
264
265
class Telem(object):
266
def __init__(self, destination_address, progress_function=None, verbose=False):
267
self.destination_address = destination_address
268
self.progress_function = progress_function
269
self.verbose = verbose
270
271
self.buffer = bytes()
272
self.connected = False
273
self.port = None
274
self.progress_log = ""
275
276
def progress(self, message):
277
message = "%s: %s" % (self.progress_tag(), message)
278
if self.progress_function is not None:
279
self.progress_function(message)
280
return
281
if not self.verbose:
282
self.progress_log += message
283
return
284
print(message)
285
286
def connect(self):
287
try:
288
self.connected = False
289
self.progress("Connecting to (%s:%u)" % self.destination_address)
290
if self.port is not None:
291
try:
292
self.port.close() # might be reopening
293
except Exception:
294
pass
295
self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
296
self.port.connect(self.destination_address)
297
self.port.setblocking(False)
298
self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
299
self.connected = True
300
self.progress("Connected")
301
except IOError as e:
302
self.progress("Failed to connect: %s" % str(e))
303
time.sleep(0.5)
304
return False
305
return True
306
307
def do_read(self) -> bytes:
308
try:
309
data = self.port.recv(1024)
310
except socket.error as e:
311
if e.errno not in [errno.EAGAIN, errno.EWOULDBLOCK]:
312
self.progress("Exception: %s" % str(e))
313
self.connected = False
314
return bytes()
315
if len(data) == 0:
316
self.progress("EOF")
317
self.connected = False
318
return bytes()
319
# print(f"Read {len(data)=} bytes {type(data)=}")
320
return data
321
322
def do_write(self, some_bytes):
323
try:
324
written = self.port.send(some_bytes)
325
except socket.error as e:
326
if e.errno in [errno.EAGAIN, errno.EWOULDBLOCK]:
327
return 0
328
self.progress("Exception: %s" % str(e))
329
raise
330
if written != len(some_bytes):
331
raise ValueError("Short write")
332
333
def update(self):
334
if not self.connected:
335
if not self.connect():
336
return
337
return self.update_read()
338
339
340
class IBusMessage(object):
341
def checksum_bytes(self, out):
342
checksum = 0xFFFF
343
for b in iter(out):
344
checksum -= b
345
return checksum
346
347
348
class IBusResponse(IBusMessage):
349
def __init__(self, some_bytes):
350
self.len = some_bytes[0]
351
checksum = self.checksum_bytes(some_bytes[:self.len-2])
352
if checksum >> 8 != some_bytes[self.len-1]:
353
raise ValueError("Checksum bad (-1)")
354
if checksum & 0xff != some_bytes[self.len-2]:
355
raise ValueError("Checksum bad (-2)")
356
self.address = some_bytes[1] & 0x0F
357
self.handle_payload_bytes(some_bytes[2:self.len-2])
358
359
360
class IBusResponse_DISCOVER(IBusResponse):
361
def handle_payload_bytes(self, payload_bytes):
362
if len(payload_bytes):
363
raise ValueError("Not expecting payload bytes (%u)" %
364
(len(payload_bytes), ))
365
366
367
class IBusResponse_GET_SENSOR_TYPE(IBusResponse):
368
def handle_payload_bytes(self, payload_bytes):
369
if len(payload_bytes) != 2:
370
raise ValueError("Expected 2 payload bytes")
371
self.sensor_type = payload_bytes[0]
372
self.sensor_length = payload_bytes[1]
373
374
375
class IBusResponse_GET_SENSOR_VALUE(IBusResponse):
376
def handle_payload_bytes(self, payload_bytes):
377
self.sensor_value = payload_bytes
378
379
def get_sensor_value(self):
380
'''returns an integer based off content'''
381
ret = 0
382
for i in range(len(self.sensor_value)):
383
x = self.sensor_value[i]
384
ret = ret | (x << (i*8))
385
return ret
386
387
388
class IBusRequest(IBusMessage):
389
def __init__(self, command, address):
390
self.command = command
391
self.address = address
392
393
def payload_bytes(self):
394
'''most requests don't have a payload'''
395
return bytearray()
396
397
def for_wire(self):
398
out = bytearray()
399
payload_bytes = self.payload_bytes()
400
payload_length = len(payload_bytes)
401
length = 1 + 1 + payload_length + 2 # len+cmd|adr+payloadlen+cksum
402
format_string = '<BB' + ('B' * payload_length)
403
out.extend(struct.pack(format_string,
404
length,
405
(self.command << 4) | self.address,
406
*payload_bytes,
407
))
408
checksum = self.checksum_bytes(out)
409
out.extend(struct.pack("<BB", checksum & 0xff, checksum >> 8))
410
return out
411
412
413
class IBusRequest_DISCOVER(IBusRequest):
414
def __init__(self, address):
415
super(IBusRequest_DISCOVER, self).__init__(0x08, address)
416
417
418
class IBusRequest_GET_SENSOR_TYPE(IBusRequest):
419
def __init__(self, address):
420
super(IBusRequest_GET_SENSOR_TYPE, self).__init__(0x09, address)
421
422
423
class IBusRequest_GET_SENSOR_VALUE(IBusRequest):
424
def __init__(self, address):
425
super(IBusRequest_GET_SENSOR_VALUE, self).__init__(0x0A, address)
426
427
428
class IBus(Telem):
429
def __init__(self, destination_address):
430
super(IBus, self).__init__(destination_address)
431
432
def progress_tag(self):
433
return "IBus"
434
435
def packet_from_buffer(self, buffer):
436
t = buffer[1] >> 4
437
if t == 0x08:
438
return IBusResponse_DISCOVER(buffer)
439
if t == 0x09:
440
return IBusResponse_GET_SENSOR_TYPE(buffer)
441
if t == 0x0A:
442
return IBusResponse_GET_SENSOR_VALUE(buffer)
443
raise ValueError("Unknown response type (%u)" % t)
444
445
def update_read(self):
446
self.buffer += self.do_read()
447
while len(self.buffer):
448
msglen = self.buffer[0]
449
if len(self.buffer) < msglen:
450
return
451
packet = self.packet_from_buffer(self.buffer[:msglen])
452
self.buffer = self.buffer[msglen:]
453
return packet
454
455
456
class WaitAndMaintain(object):
457
def __init__(self,
458
test_suite,
459
minimum_duration=None,
460
progress_print_interval=1,
461
timeout=30,
462
epsilon=None,
463
comparator=None,
464
fn=None,
465
fn_interval=None,
466
):
467
self.test_suite = test_suite
468
self.minimum_duration = minimum_duration
469
self.achieving_duration_start = None
470
self.timeout = timeout
471
self.epsilon = epsilon
472
self.last_progress_print = 0
473
self.progress_print_interval = progress_print_interval
474
self.comparator = comparator
475
if self.minimum_duration is not None:
476
if self.timeout < self.minimum_duration:
477
raise ValueError("timeout less than min duration")
478
479
self.fn = fn
480
self.fn_interval = fn_interval
481
self.last_fn_run_time = 0
482
483
def run(self):
484
self.announce_test_start()
485
486
tstart = self.test_suite.get_sim_time_cached()
487
while True:
488
now = self.test_suite.get_sim_time_cached()
489
current_value = self.get_current_value()
490
if now - self.last_progress_print > self.progress_print_interval:
491
self.print_progress(now, current_value)
492
self.last_progress_print = now
493
494
# check for timeout
495
if now - tstart > self.timeout:
496
self.print_failure_text(now, current_value)
497
raise self.timeoutexception()
498
499
# call supplied function if appropriate:
500
if (self.fn is not None and
501
now - self.last_fn_run_time > self.fn_interval):
502
self.fn()
503
self.last_fn_run_time = now
504
505
# handle the case where we are are achieving our value:
506
if self.validate_value(current_value):
507
if self.achieving_duration_start is None:
508
self.achieving_duration_start = now
509
if (self.minimum_duration is None or
510
now - self.achieving_duration_start > self.minimum_duration):
511
self.announce_success()
512
return True
513
continue
514
515
# handle the case where we are not achieving our value:
516
self.achieving_duration_start = None
517
518
def progress(self, text):
519
self.test_suite.progress(text)
520
521
def announce_test_start(self):
522
self.progress(self.announce_start_text())
523
524
def announce_success(self):
525
self.progress(self.success_text())
526
527
def print_progress(self, now, value):
528
text = self.progress_text(value)
529
if self.achieving_duration_start is not None:
530
delta = now - self.achieving_duration_start
531
text += f" (maintain={delta:.1f}/{self.minimum_duration})"
532
self.progress(text)
533
534
def print_failure_text(self, now, value):
535
'''optionally print a more detailed error string'''
536
pass
537
538
def progress_text(self, value):
539
return f"want={self.get_target_value()} got={value}"
540
541
def validate_value(self, value):
542
target_value = self.get_target_value()
543
if self.comparator is not None:
544
return self.comparator(value, target_value)
545
546
if self.epsilon is not None:
547
return (abs(value - target_value) <= self.epsilon)
548
549
return value == target_value
550
551
def timeoutexception(self):
552
return AutoTestTimeoutException("Failed to attain or maintain value")
553
554
def success_text(self):
555
return f"{type(self)} Success"
556
557
558
class WaitAndMaintainLocation(WaitAndMaintain):
559
def __init__(self, test_suite, target, accuracy=5, height_accuracy=1, **kwargs):
560
super(WaitAndMaintainLocation, self).__init__(test_suite, **kwargs)
561
self.target = target
562
self.height_accuracy = height_accuracy
563
self.accuracy = accuracy
564
565
def announce_start_text(self):
566
t = self.target
567
if self.height_accuracy is not None:
568
return ("Waiting for distance to Location (%.4f, %.4f, %.2f) (h_err<%f, v_err<%.2f " %
569
(t.lat, t.lng, t.alt*0.01, self.accuracy, self.height_accuracy))
570
return ("Waiting for distance to Location (%.4f, %.4f) (h_err<%f" %
571
(t.lat, t.lng, self.accuracy))
572
573
def get_target_value(self):
574
return self.loc
575
576
def get_current_value(self):
577
return self.test_suite.mav.location()
578
579
def horizontal_error(self, value):
580
return self.test_suite.get_distance(value, self.target)
581
582
def vertical_error(self, value):
583
return math.fabs(value.alt*0.01 - self.target.alt*0.01)
584
585
def validate_value(self, value):
586
if self.horizontal_error(value) > self.accuracy:
587
return False
588
589
if self.height_accuracy is None:
590
return True
591
592
if self.vertical_error(value) > self.height_accuracy:
593
return False
594
595
return True
596
597
def success_text(self):
598
return "Reached location"
599
600
def timeoutexception(self):
601
return AutoTestTimeoutException("Failed to attain location")
602
603
def progress_text(self, current_value):
604
if self.height_accuracy is not None:
605
return (f"Want=({self.target.lat:.7f},{self.target.lng:.7f},{self.target.alt:.2f}) Got=({current_value.lat:.7f},{current_value.lng:.7f},{current_value.alt:.2f}) dist={self.horizontal_error(current_value):.2f} vdist={self.vertical_error(current_value):.2f}") # noqa
606
607
return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}")
608
609
610
class WaitAndMaintainEKFFlags(WaitAndMaintain):
611
'''Waits for EKF status flags to include required_flags and have
612
error_bits *not* set.'''
613
def __init__(self, test_suite, required_flags, error_bits, **kwargs):
614
super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs)
615
self.required_flags = required_flags
616
self.error_bits = error_bits
617
self.last_EKF_STATUS_REPORT = None
618
619
def announce_start_text(self):
620
return f"Waiting for EKF value {self.required_flags}"
621
622
def get_current_value(self):
623
self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10)
624
return self.last_EKF_STATUS_REPORT.flags
625
626
def validate_value(self, value):
627
if value & self.error_bits:
628
return False
629
630
if (value & self.required_flags) != self.required_flags:
631
return False
632
633
return True
634
635
def success_text(self):
636
return "EKF Flags OK"
637
638
def timeoutexception(self):
639
self.progress("Last EKF status report:")
640
self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT))
641
642
return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}")
643
644
def progress_text(self, current_value):
645
error_bits = current_value & self.error_bits
646
return (f"Want={self.required_flags} got={current_value} errors={error_bits}")
647
648
def ekf_flags_string(self, bits):
649
ret = []
650
for i in range(0, 16):
651
bit = 1 << i
652
try:
653
if not bits & bit:
654
continue
655
name = mavutil.mavlink.enums["ESTIMATOR_STATUS_FLAGS"][bit].name
656
trimmed_name = name.removeprefix("ESTIMATOR_")
657
ret.append(trimmed_name)
658
except KeyError:
659
ret.append(str(bit))
660
return "|".join(ret)
661
662
def failure_text(self, now, current_value):
663
components = []
664
components.append(("want", self.ekf_flags_string(self.required_flags)))
665
666
missing_bits = self.required_flags & ~current_value
667
if missing_bits:
668
components.append(("missing", self.ekf_flags_string(missing_bits)))
669
670
error_bits = current_value & self.error_bits
671
if error_bits:
672
components.append(("errors", self.ekf_flags_string(error_bits)))
673
674
return " ".join([f"{n}={v}" for (n, v) in components])
675
676
def print_failure_text(self, now, current_value):
677
self.progress(self.failure_text(now, current_value))
678
679
680
class WaitAndMaintainArmed(WaitAndMaintain):
681
def get_current_value(self):
682
return self.test_suite.armed()
683
684
def get_target_value(self):
685
return True
686
687
def announce_start_text(self):
688
return "Ensuring vehicle remains armed"
689
690
691
class WaitAndMaintainDisarmed(WaitAndMaintain):
692
def get_current_value(self):
693
return self.test_suite.armed()
694
695
def get_target_value(self):
696
return False
697
698
def announce_start_text(self):
699
return "Ensuring vehicle remains disarmed"
700
701
702
class WaitAndMaintainServoChannelValue(WaitAndMaintain):
703
def __init__(self, test_suite, channel, value, **kwargs):
704
super(WaitAndMaintainServoChannelValue, self).__init__(test_suite, **kwargs)
705
self.channel = channel
706
self.value = value
707
708
def announce_start_text(self):
709
str_operator = ""
710
if self.comparator == operator.lt:
711
str_operator = "less than "
712
elif self.comparator == operator.gt:
713
str_operator = "more than "
714
715
return f"Waiting for SERVO_OUTPUT_RAW.servo{self.channel}_value value {str_operator}{self.value}"
716
717
def get_target_value(self):
718
return self.value
719
720
def get_current_value(self):
721
m = self.test_suite.assert_receive_message('SERVO_OUTPUT_RAW', timeout=10)
722
channel_field = "servo%u_raw" % self.channel
723
m_value = getattr(m, channel_field, None)
724
if m_value is None:
725
raise ValueError(f"message ({str(m)}) has no field {channel_field}")
726
727
self.last_SERVO_OUTPUT_RAW = m
728
return m_value
729
730
731
class WaitAndMaintainAttitude(WaitAndMaintain):
732
def __init__(self, test_suite, desroll=None, despitch=None, **kwargs):
733
super().__init__(test_suite, **kwargs)
734
self.desroll = desroll
735
self.despitch = despitch
736
737
if self.desroll is None and self.despitch is None:
738
raise ValueError("despitch or desroll must be supplied")
739
740
def announce_start_text(self):
741
conditions = []
742
if self.desroll is not None:
743
conditions.append(f"roll={self.desroll}")
744
if self.despitch is not None:
745
conditions.append(f"pitch={self.despitch}")
746
747
return f"Waiting for {' and '.join(conditions)}"
748
749
def get_target_value(self):
750
return (self.desroll, self.despitch)
751
752
def get_current_value(self):
753
m = self.test_suite.assert_receive_message('ATTITUDE', timeout=10)
754
self.last_ATTITUDE = m
755
return (math.degrees(m.roll), math.degrees(m.pitch))
756
757
def validate_value(self, value):
758
(candidate_roll, candidate_pitch) = value
759
760
if self.desroll is not None:
761
roll_error = abs(self.desroll - candidate_roll)
762
if roll_error > self.epsilon:
763
return False
764
765
if self.despitch is not None:
766
pitch_error = abs(self.despitch - candidate_pitch)
767
if pitch_error > self.epsilon:
768
return False
769
770
return True
771
772
def success_text(self):
773
return "Attained attitude"
774
775
def timeoutexception(self):
776
return AutoTestTimeoutException("Failed to attain attitude")
777
778
def progress_text(self, current_value):
779
(achieved_roll, achieved_pitch) = current_value
780
axis_progress = []
781
782
if self.desroll is not None:
783
axis_progress.append(f"r={achieved_roll: >8.3f} des-r={self.desroll}")
784
785
if self.despitch is not None:
786
axis_progress.append(f"p={achieved_pitch: >8.3f} des-p={self.despitch}")
787
788
return " ".join(axis_progress)
789
790
791
class MSP_Generic(Telem):
792
def __init__(self, destination_address):
793
super(MSP_Generic, self).__init__(destination_address)
794
795
self.callback = None
796
797
self.STATE_IDLE = "IDLE"
798
self.STATE_WANT_HEADER_DOLLARS = "WANT_DOLLARS"
799
self.STATE_WANT_HEADER_M = "WANT_M"
800
self.STATE_WANT_HEADER_GT = "WANT_GT"
801
self.STATE_WANT_DATA_SIZE = "WANT_DATA_SIZE"
802
self.STATE_WANT_COMMAND = "WANT_COMMAND"
803
self.STATE_WANT_DATA = "WANT_DATA"
804
self.STATE_WANT_CHECKSUM = "WANT_CHECKSUM"
805
806
self.state = self.STATE_IDLE
807
808
def progress(self, message):
809
print("MSP: %s" % message)
810
811
def set_state(self, state):
812
# self.progress("Moving to state (%s)" % state)
813
self.state = state
814
815
def init_checksum(self, b):
816
self.checksum = 0
817
self.add_to_checksum(b)
818
819
def add_to_checksum(self, b):
820
self.checksum ^= (b & 0xFF)
821
822
def process_command(self, cmd, data):
823
if self.callback is not None:
824
self.callback(cmd, data)
825
else:
826
print("cmd=%s" % str(cmd))
827
828
def update_read(self):
829
for byte in self.do_read():
830
c = chr(byte)
831
# print("Got (0x%02x) (%s) (%s) state=%s" % (byte, chr(byte), str(type(byte)), self.state))
832
if self.state == self.STATE_IDLE:
833
# reset state
834
self.set_state(self.STATE_WANT_HEADER_DOLLARS)
835
# deliberate fallthrough right here
836
if self.state == self.STATE_WANT_HEADER_DOLLARS:
837
if c == '$':
838
self.set_state(self.STATE_WANT_HEADER_M)
839
continue
840
if self.state == self.STATE_WANT_HEADER_M:
841
if c != 'M':
842
raise Exception("Malformed packet")
843
self.set_state(self.STATE_WANT_HEADER_GT)
844
continue
845
if self.state == self.STATE_WANT_HEADER_GT:
846
if c != '>':
847
raise Exception("Malformed packet")
848
self.set_state(self.STATE_WANT_DATA_SIZE)
849
continue
850
if self.state == self.STATE_WANT_DATA_SIZE:
851
self.data_size = byte
852
self.set_state(self.STATE_WANT_COMMAND)
853
self.data = bytearray()
854
self.checksum = 0
855
self.add_to_checksum(byte)
856
continue
857
if self.state == self.STATE_WANT_COMMAND:
858
self.command = byte
859
self.add_to_checksum(byte)
860
if self.data_size != 0:
861
self.set_state(self.STATE_WANT_DATA)
862
else:
863
self.set_state(self.STATE_WANT_CHECKSUM)
864
continue
865
if self.state == self.STATE_WANT_DATA:
866
self.add_to_checksum(byte)
867
self.data.append(byte)
868
if len(self.data) == self.data_size:
869
self.set_state(self.STATE_WANT_CHECKSUM)
870
continue
871
if self.state == self.STATE_WANT_CHECKSUM:
872
if self.checksum != byte:
873
raise Exception("Checksum fail (want=0x%02x calced=0x%02x" %
874
(byte, self.checksum))
875
self.process_command(self.command, self.data)
876
self.set_state(self.STATE_IDLE)
877
878
879
class MSP_DJI(MSP_Generic):
880
FRAME_GPS_RAW = 106
881
FRAME_ATTITUDE = 108
882
883
def __init__(self, destination_address):
884
super(MSP_DJI, self).__init__(destination_address)
885
self.callback = self.command_callback
886
self.frames = {}
887
888
class Frame(object):
889
def __init__(self, data):
890
self.data = data
891
892
def intn(self, offset, count):
893
ret = 0
894
for i in range(offset, offset+count):
895
ret = ret | (ord(self.data[i]) << ((i-offset)*8))
896
return ret
897
898
def int32(self, offset):
899
t = struct.unpack("<i", self.data[offset:offset+4])
900
return t[0]
901
902
def int16(self, offset):
903
t = struct.unpack("<h", self.data[offset:offset+2])
904
return t[0]
905
906
class FrameATTITUDE(Frame):
907
def roll(self):
908
'''roll in degrees'''
909
return self.int16(0) * 10
910
911
def pitch(self):
912
'''pitch in degrees'''
913
return self.int16(2) * 10
914
915
def yaw(self):
916
'''yaw in degrees'''
917
return self.int16(4)
918
919
class FrameGPS_RAW(Frame):
920
'''see gps_state_s'''
921
def fix_type(self):
922
return self.uint8(0)
923
924
def num_sats(self):
925
return self.uint8(1)
926
927
def lat(self):
928
return self.int32(2) / 1e7
929
930
def lon(self):
931
return self.int32(6) / 1e7
932
933
def LocationInt(self):
934
# other fields are available, I'm just lazy
935
return LocationInt(self.int32(2), self.int32(6), 0, 0)
936
937
def command_callback(self, frametype, data):
938
# print("X: %s %s" % (str(frametype), str(data)))
939
if frametype == MSP_DJI.FRAME_ATTITUDE:
940
frame = MSP_DJI.FrameATTITUDE(data)
941
elif frametype == MSP_DJI.FRAME_GPS_RAW:
942
frame = MSP_DJI.FrameGPS_RAW(data)
943
else:
944
return
945
self.frames[frametype] = frame
946
947
def get_frame(self, frametype):
948
return self.frames[frametype]
949
950
951
class LTM(Telem):
952
def __init__(self, destination_address):
953
super(LTM, self).__init__(destination_address)
954
955
self.HEADER1 = 0x24
956
self.HEADER2 = 0x54
957
958
self.FRAME_G = 0x47
959
self.FRAME_A = 0x41
960
self.FRAME_S = 0x53
961
962
self.frame_lengths = {
963
self.FRAME_G: 18,
964
self.FRAME_A: 10,
965
self.FRAME_S: 11,
966
}
967
self.frame_lengths = {
968
self.FRAME_G: 18,
969
self.FRAME_A: 10,
970
self.FRAME_S: 11,
971
}
972
973
self.data_by_id = {}
974
self.frames = {}
975
976
def g(self):
977
return self.frames.get(self.FRAME_G, None)
978
979
def a(self):
980
return self.frames.get(self.FRAME_A, None)
981
982
def s(self):
983
return self.frames.get(self.FRAME_S, None)
984
985
def progress_tag(self):
986
return "LTM"
987
988
def handle_data(self, dataid, value):
989
self.progress("%u=%u" % (dataid, value))
990
self.data_by_id[dataid] = value
991
992
def consume_frame(self):
993
b2 = self.buffer[2]
994
frame_type = b2
995
frame_length = self.frame_lengths[frame_type]
996
# check frame CRC
997
crc = 0
998
count = 0
999
for c in self.buffer[3:frame_length-1]:
1000
crc ^= c
1001
count += 1
1002
buffer_crc = self.buffer[frame_length-1]
1003
if crc != buffer_crc:
1004
raise NotAchievedException("Invalid checksum on frame type %s" % str(chr(frame_type)))
1005
# self.progress("Received valid %s frame" % str(chr(frame_type)))
1006
1007
class Frame(object):
1008
def __init__(self, buffer):
1009
self.buffer = buffer
1010
1011
def intn(self, offset, count):
1012
ret = 0
1013
for i in range(offset, offset+count):
1014
ret = ret | (ord(self.buffer[i]) << ((i-offset)*8))
1015
return ret
1016
1017
def int32(self, offset):
1018
t = struct.unpack("<i", self.buffer[offset:offset+4])
1019
return t[0]
1020
# return self.intn(offset, 4)
1021
1022
def int16(self, offset):
1023
t = struct.unpack("<h", self.buffer[offset:offset+2])
1024
return t[0]
1025
# return self.intn(offset, 2)
1026
1027
class FrameG(Frame):
1028
def __init__(self, buffer):
1029
super(FrameG, self,).__init__(buffer)
1030
1031
def lat(self):
1032
return self.int32(3)
1033
1034
def lon(self):
1035
return self.int32(7)
1036
1037
def gndspeed(self):
1038
return self.buffer[11]
1039
1040
def alt(self):
1041
return self.int32(12)
1042
1043
def sats(self):
1044
s = self.buffer[16]
1045
return (s >> 2)
1046
1047
def fix_type(self):
1048
s = self.buffer[16]
1049
return s & 0b11
1050
1051
class FrameA(Frame):
1052
def __init__(self, buffer):
1053
super(FrameA, self,).__init__(buffer)
1054
1055
def pitch(self):
1056
return self.int16(3)
1057
1058
def roll(self):
1059
return self.int16(5)
1060
1061
def hdg(self):
1062
return self.int16(7)
1063
1064
class FrameS(Frame):
1065
def __init__(self, buffer):
1066
super(FrameS, self,).__init__(buffer)
1067
1068
if frame_type == self.FRAME_G:
1069
frame = FrameG(self.buffer[0:frame_length-1])
1070
elif frame_type == self.FRAME_A:
1071
frame = FrameA(self.buffer[0:frame_length-1])
1072
elif frame_type == self.FRAME_S:
1073
frame = FrameS(self.buffer[0:frame_length-1])
1074
else:
1075
raise NotAchievedException("Bad frame?!?!?!")
1076
self.buffer = self.buffer[frame_length:]
1077
self.frames[frame_type] = frame
1078
1079
def update_read(self):
1080
self.buffer += self.do_read()
1081
while len(self.buffer):
1082
if len(self.buffer) == 0:
1083
break
1084
b0 = self.buffer[0]
1085
if b0 != self.HEADER1:
1086
self.bad_chars += 1
1087
self.buffer = self.buffer[1:]
1088
continue
1089
b1 = self.buffer[1]
1090
if b1 != self.HEADER2:
1091
self.bad_chars += 1
1092
self.buffer = self.buffer[1:]
1093
continue
1094
b2 = self.buffer[2]
1095
if b2 not in [self.FRAME_G, self.FRAME_A, self.FRAME_S]:
1096
self.bad_chars += 1
1097
self.buffer = self.buffer[1:]
1098
continue
1099
frame_len = self.frame_lengths[b2]
1100
if len(self.buffer) < frame_len:
1101
continue
1102
self.consume_frame()
1103
1104
def get_data(self, dataid):
1105
try:
1106
return self.data_by_id[dataid]
1107
except KeyError:
1108
pass
1109
return None
1110
1111
1112
class CRSF(Telem):
1113
def __init__(self, destination_address):
1114
super(CRSF, self).__init__(destination_address)
1115
1116
self.dataid_vtx_frame = 0
1117
self.dataid_vtx_telem = 1
1118
self.dataid_vtx_unknown = 2
1119
1120
self.data_id_map = {
1121
self.dataid_vtx_frame: bytearray([0xC8, 0x8, 0xF, 0xCE, 0x30, 0x8, 0x16, 0xE9, 0x0, 0x5F]),
1122
self.dataid_vtx_telem: bytearray([0xC8, 0x7, 0x10, 0xCE, 0xE, 0x16, 0x65, 0x0, 0x1B]),
1123
self.dataid_vtx_unknown: bytearray([0xC8, 0x9, 0x8, 0x0, 0x9E, 0x0, 0x0, 0x0, 0x0, 0x0, 0x95]),
1124
}
1125
1126
def write_data_id(self, dataid):
1127
self.do_write(self.data_id_map[dataid])
1128
1129
def progress_tag(self):
1130
return "CRSF"
1131
1132
1133
class DEVO(Telem):
1134
def __init__(self, destination_address):
1135
super(DEVO, self).__init__(destination_address)
1136
1137
self.HEADER = 0xAA
1138
self.frame_length = 20
1139
1140
# frame is 'None' until we receive a frame with VALID header and checksum
1141
self.frame = None
1142
self.bad_chars = 0
1143
1144
def progress_tag(self):
1145
return "DEVO"
1146
1147
def consume_frame(self):
1148
# check frame checksum
1149
checksum = 0
1150
for c in self.buffer[:self.frame_length-1]:
1151
checksum += c
1152
checksum &= 0xff # since we receive 8 bit checksum
1153
buffer_checksum = self.buffer[self.frame_length-1]
1154
if checksum != buffer_checksum:
1155
raise NotAchievedException("Invalid checksum")
1156
1157
class FRAME(object):
1158
def __init__(self, buffer):
1159
self.buffer = buffer
1160
1161
def int32(self, offset):
1162
t = struct.unpack("<i", self.buffer[offset:offset+4])
1163
return t[0]
1164
1165
def int16(self, offset):
1166
t = struct.unpack("<h", self.buffer[offset:offset+2])
1167
return t[0]
1168
1169
def lon(self):
1170
return self.int32(1)
1171
1172
def lat(self):
1173
return self.int32(5)
1174
1175
def alt(self):
1176
return self.int32(9)
1177
1178
def speed(self):
1179
return self.int16(13)
1180
1181
def temp(self):
1182
return self.int16(15)
1183
1184
def volt(self):
1185
return self.int16(17)
1186
1187
self.frame = FRAME(self.buffer[0:self.frame_length-1])
1188
self.buffer = self.buffer[self.frame_length:]
1189
1190
def update_read(self):
1191
self.buffer += self.do_read()
1192
while len(self.buffer):
1193
if len(self.buffer) == 0:
1194
break
1195
b0 = self.buffer[0]
1196
if b0 != self.HEADER:
1197
self.bad_chars += 1
1198
self.buffer = self.buffer[1:]
1199
continue
1200
if len(self.buffer) < self.frame_length:
1201
continue
1202
self.consume_frame()
1203
1204
1205
class FRSky(Telem):
1206
def __init__(self, destination_address, verbose=False):
1207
super(FRSky, self).__init__(destination_address, verbose=verbose)
1208
1209
self.dataid_GPS_ALT_BP = 0x01
1210
self.dataid_TEMP1 = 0x02
1211
self.dataid_FUEL = 0x04
1212
self.dataid_TEMP2 = 0x05
1213
self.dataid_GPS_ALT_AP = 0x09
1214
self.dataid_BARO_ALT_BP = 0x10
1215
self.dataid_GPS_SPEED_BP = 0x11
1216
self.dataid_GPS_LONG_BP = 0x12
1217
self.dataid_GPS_LAT_BP = 0x13
1218
self.dataid_GPS_COURS_BP = 0x14
1219
self.dataid_GPS_SPEED_AP = 0x19
1220
self.dataid_GPS_LONG_AP = 0x1A
1221
self.dataid_GPS_LAT_AP = 0x1B
1222
self.dataid_BARO_ALT_AP = 0x21
1223
self.dataid_GPS_LONG_EW = 0x22
1224
self.dataid_GPS_LAT_NS = 0x23
1225
self.dataid_CURRENT = 0x28
1226
self.dataid_VFAS = 0x39
1227
1228
1229
class FRSkyD(FRSky):
1230
def __init__(self, destination_address):
1231
super(FRSkyD, self).__init__(destination_address)
1232
1233
self.state_WANT_START_STOP_D = 16,
1234
self.state_WANT_ID = 17
1235
self.state_WANT_BYTE1 = 18
1236
self.state_WANT_BYTE2 = 19
1237
1238
self.START_STOP_D = 0x5E
1239
self.BYTESTUFF_D = 0x5D
1240
1241
self.state = self.state_WANT_START_STOP_D
1242
1243
self.data_by_id = {}
1244
self.bad_chars = 0
1245
1246
def progress_tag(self):
1247
return "FRSkyD"
1248
1249
def handle_data(self, dataid, value):
1250
self.progress("%u=%u" % (dataid, value))
1251
self.data_by_id[dataid] = value
1252
1253
def update_read(self):
1254
self.buffer += self.do_read()
1255
consume = None
1256
while len(self.buffer):
1257
if consume is not None:
1258
self.buffer = self.buffer[consume:]
1259
if len(self.buffer) == 0:
1260
break
1261
consume = 1
1262
b = self.buffer[0]
1263
if self.state == self.state_WANT_START_STOP_D:
1264
if b != self.START_STOP_D:
1265
# we may come into a stream mid-way, so we can't judge
1266
self.bad_chars += 1
1267
continue
1268
self.state = self.state_WANT_ID
1269
continue
1270
elif self.state == self.state_WANT_ID:
1271
self.dataid = b
1272
self.state = self.state_WANT_BYTE1
1273
continue
1274
elif self.state in [self.state_WANT_BYTE1, self.state_WANT_BYTE2]:
1275
if b == 0x5D:
1276
# byte-stuffed
1277
if len(self.buffer) < 2:
1278
# try again in a little while
1279
consume = 0
1280
return
1281
if self.buffer[1] == 0x3E:
1282
b = self.START_STOP_D
1283
elif self.buffer[1] == 0x3D:
1284
b = self.BYTESTUFF_D
1285
else:
1286
raise ValueError("Unknown stuffed byte")
1287
consume = 2
1288
if self.state == self.state_WANT_BYTE1:
1289
self.b1 = b
1290
self.state = self.state_WANT_BYTE2
1291
continue
1292
1293
data = self.b1 | b << 8
1294
self.handle_data(self.dataid, data)
1295
self.state = self.state_WANT_START_STOP_D
1296
1297
def get_data(self, dataid):
1298
try:
1299
return self.data_by_id[dataid]
1300
except KeyError:
1301
pass
1302
return None
1303
1304
1305
class SPortPacket(object):
1306
def __init__(self):
1307
self.START_STOP_SPORT = 0x7E
1308
self.BYTESTUFF_SPORT = 0x7D
1309
1310
1311
class SPortUplinkPacket(SPortPacket):
1312
def __init__(self, appid0, appid1, data0, data1, data2, data3):
1313
super(SPortUplinkPacket, self).__init__()
1314
self.appid0 = appid0
1315
self.appid1 = appid1
1316
self.data0 = data0
1317
self.data1 = data1
1318
self.data2 = data2
1319
self.data3 = data3
1320
self.SENSOR_ID_UPLINK_ID = 0x0D
1321
self.SPORT_UPLINK_FRAME = 0x30
1322
self.uplink_id = self.SENSOR_ID_UPLINK_ID
1323
self.frame = self.SPORT_UPLINK_FRAME
1324
1325
def packed(self):
1326
return struct.pack(
1327
'<BBBBBBBB',
1328
self.uplink_id,
1329
self.frame,
1330
self.appid0 & 0xff,
1331
self.appid1 & 0xff,
1332
self.data0 & 0xff,
1333
self.data1 & 0xff,
1334
self.data2 & 0xff,
1335
self.data3 & 0xff,
1336
)
1337
1338
def update_checksum(self, byte):
1339
self.checksum += byte
1340
self.checksum += self.checksum >> 8
1341
self.checksum &= 0xFF
1342
1343
def checksum(self):
1344
self.checksum = 0
1345
self.update_checksum(self.frame & 0xff)
1346
self.update_checksum(self.appid0 & 0xff)
1347
self.update_checksum(self.appid1 & 0xff)
1348
self.update_checksum(self.data0 & 0xff)
1349
self.update_checksum(self.data1 & 0xff)
1350
self.update_checksum(self.data2 & 0xff)
1351
self.update_checksum(self.data3 & 0xff)
1352
self.checksum = 0xff - ((self.checksum & 0xff) + (self.checksum >> 8))
1353
return self.checksum & 0xff
1354
1355
def for_wire(self):
1356
out = bytearray()
1357
out.extend(self.packed())
1358
out.extend(struct.pack('<B', self.checksum()))
1359
stuffed = bytearray()
1360
stuffed.extend(struct.pack('<B', self.START_STOP_SPORT))
1361
for pbyte in out:
1362
if pbyte in [self.BYTESTUFF_SPORT,
1363
self.START_STOP_SPORT]:
1364
# bytestuff
1365
stuffed.append(self.BYTESTUFF_SPORT)
1366
stuffed.append(pbyte ^ self.SPORT_FRAME_XOR)
1367
else:
1368
stuffed.append(pbyte)
1369
return stuffed
1370
1371
1372
class SPortPollPacket(SPortPacket):
1373
def __init__(self, sensor):
1374
super(SPortPollPacket, self).__init__()
1375
self.sensor = sensor
1376
1377
def for_wire(self):
1378
return struct.pack(
1379
'<BB',
1380
self.START_STOP_SPORT,
1381
self.sensor & 0xff,
1382
)
1383
1384
1385
class MAVliteMessage(object):
1386
def __init__(self, msgid, body):
1387
self.msgid = msgid
1388
self.body = body
1389
self.SENSOR_ID_UPLINK_ID = 0x0D
1390
self.SPORT_UPLINK_FRAME = 0x30
1391
1392
def checksum_bytes(self, some_bytes):
1393
checksum = 0
1394
for b in some_bytes:
1395
checksum += b
1396
checksum += checksum >> 8
1397
checksum &= 0xFF
1398
return checksum
1399
1400
def to_sport_packets(self):
1401
ret = []
1402
all_bytes = bytearray([len(self.body), self.msgid])
1403
all_bytes.extend(self.body)
1404
1405
# insert sequence numbers:
1406
seq = 0
1407
sequenced = bytearray()
1408
while len(all_bytes):
1409
chunk = all_bytes[0:5]
1410
all_bytes = all_bytes[5:]
1411
sequenced.append(seq)
1412
sequenced.extend(chunk)
1413
seq += 1
1414
1415
# we may need another sport packet just for the checksum:
1416
if len(sequenced) % 6 == 0:
1417
sequenced.append(seq)
1418
seq += 1
1419
1420
checksum = self.checksum_bytes(sequenced)
1421
sequenced.append(checksum)
1422
1423
while len(sequenced):
1424
chunk = sequenced[0:6]
1425
sequenced = sequenced[6:]
1426
chunk.extend([0] * (6-len(chunk))) # pad to 6
1427
packet = SPortUplinkPacket(
1428
*chunk
1429
)
1430
ret.append(packet)
1431
return ret
1432
1433
1434
class SPortToMAVlite(object):
1435
def __init__(self):
1436
self.state_WANT_LEN = "want len"
1437
self.state_WANT_MSGID = "want msgid"
1438
self.state_WANT_PAYLOAD = "want payload"
1439
self.state_WANT_CHECKSUM = "want checksum"
1440
self.state_MESSAGE_RECEIVED = "message received"
1441
1442
self.reset()
1443
1444
def progress(self, message):
1445
print("SPortToMAVLite: %s" % message)
1446
1447
def reset(self):
1448
self.want_seq = 0
1449
self.all_bytes = bytearray()
1450
self.payload = bytearray()
1451
self.state = self.state_WANT_LEN
1452
1453
def checksum_bytes(self, some_bytes):
1454
checksum = 0
1455
for b in some_bytes:
1456
checksum += b
1457
checksum += checksum >> 8
1458
checksum &= 0xFF
1459
return checksum
1460
1461
def downlink_handler(self, some_bytes):
1462
'''adds some_bytes into a mavlite message'''
1463
if some_bytes[0] == 0x00:
1464
self.reset()
1465
if some_bytes[0] != self.want_seq:
1466
raise NotAchievedException("Unexpected seqno; want=%u got=%u" %
1467
(self.want_seq, some_bytes[0]))
1468
self.all_bytes.append(some_bytes[0])
1469
self.want_seq += 1
1470
for byte in some_bytes[1:]:
1471
if self.state == self.state_WANT_LEN:
1472
self.payload_len = byte
1473
self.all_bytes.append(byte)
1474
self.state = self.state_WANT_MSGID
1475
continue
1476
if self.state == self.state_WANT_MSGID:
1477
self.msgid = byte
1478
self.all_bytes.append(byte)
1479
if self.payload_len == 0:
1480
self.state = self.state_WANT_CHECKSUM
1481
else:
1482
self.state = self.state_WANT_PAYLOAD
1483
continue
1484
if self.state == self.state_WANT_PAYLOAD:
1485
self.payload.append(byte)
1486
self.all_bytes.append(byte)
1487
if len(self.payload) == self.payload_len:
1488
self.state = self.state_WANT_CHECKSUM
1489
continue
1490
if self.state == self.state_WANT_CHECKSUM:
1491
calculated_checksum = self.checksum_bytes(self.all_bytes)
1492
if calculated_checksum != byte:
1493
raise Exception("Checksum failure (calc=%u) (recv=%u)" % (calculated_checksum, byte))
1494
self.state = self.state_MESSAGE_RECEIVED
1495
break
1496
1497
def get_message(self):
1498
if self.state != self.state_MESSAGE_RECEIVED:
1499
raise Exception("Wrong state")
1500
return MAVliteMessage(self.msgid, self.payload)
1501
1502
1503
class FRSkySPort(FRSky):
1504
def __init__(self, destination_address, verbose=True, get_time=time.time):
1505
super(FRSkySPort, self).__init__(
1506
destination_address,
1507
verbose=verbose
1508
)
1509
1510
self.get_time = get_time
1511
1512
self.state_SEND_POLL = "sendpoll"
1513
self.state_WANT_FRAME_TYPE = "want_frame_type"
1514
self.state_WANT_ID1 = "want_id1"
1515
self.state_WANT_ID2 = "want id2"
1516
self.state_WANT_DATA = "want data"
1517
self.state_WANT_CRC = "want crc"
1518
1519
self.START_STOP_SPORT = 0x7E
1520
self.BYTESTUFF_SPORT = 0x7D
1521
self.SPORT_DATA_FRAME = 0x10
1522
self.SPORT_DOWNLINK_FRAME = 0x32
1523
self.SPORT_FRAME_XOR = 0x20
1524
1525
self.SENSOR_ID_VARIO = 0x00 # Sensor ID 0
1526
self.SENSOR_ID_FAS = 0x22 # Sensor ID 2
1527
self.SENSOR_ID_GPS = 0x83 # Sensor ID 3
1528
self.SENSOR_ID_RPM = 0xE4 # Sensor ID 4
1529
self.SENSOR_ID_SP2UR = 0xC6 # Sensor ID 6
1530
self.SENSOR_ID_27 = 0x1B # Sensor ID 27
1531
1532
# MAVlite support:
1533
self.SENSOR_ID_DOWNLINK1_ID = 0x34
1534
self.SENSOR_ID_DOWNLINK2_ID = 0x67
1535
self.SENSOR_ID_UPLINK_ID = 0x0D
1536
1537
self.state = self.state_WANT_FRAME_TYPE
1538
1539
self.data_by_id = {}
1540
self.dataid_counts = {}
1541
self.bad_chars = 0
1542
1543
self.poll_sent = 0
1544
self.sensor_id_poll_counts = {}
1545
1546
self.id_descriptions = {
1547
0x5000: "status text (dynamic)",
1548
0x5006: "Attitude and range (dynamic)",
1549
0x800: "GPS lat or lon (600 with 1 sensor)",
1550
0x5005: "Vel and Yaw",
1551
0x5001: "AP status",
1552
0x5002: "GPS Status",
1553
0x5004: "Home",
1554
0x5008: "Battery 2 status",
1555
0x5003: "Battery 1 status",
1556
0x5007: "parameters",
1557
0x500A: "rpm",
1558
0x500B: "terrain",
1559
0x500C: "wind",
1560
1561
# SPort non-passthrough:
1562
0x082F: "GALT", # gps altitude integer cm
1563
0x040F: "TMP1", # Tmp1
1564
0x060F: "Fuel", # fuel % 0-100
1565
0x041F: "TMP2", # Tmp2
1566
0x010F: "ALT", # baro alt cm
1567
0x083F: "GSPD", # gps speed integer mm/s
1568
0x084F: "HDG", # yaw in cd
1569
0x020F: "CURR", # current dA
1570
0x011F: "VSPD", # vertical speed cm/s
1571
0x021F: "VFAS", # battery 1 voltage cV
1572
# 0x800: "GPS", ## comments as duplicated dictionary key
1573
0x050E: "RPM1",
1574
1575
0x34: "DOWNLINK1_ID",
1576
0x67: "DOWNLINK2_ID",
1577
0x0D: "UPLINK_ID",
1578
}
1579
1580
self.sensors_to_poll = [
1581
self.SENSOR_ID_VARIO,
1582
self.SENSOR_ID_FAS,
1583
self.SENSOR_ID_GPS,
1584
self.SENSOR_ID_RPM,
1585
self.SENSOR_ID_SP2UR,
1586
]
1587
self.next_sensor_id_to_poll = 0 # offset into sensors_to_poll
1588
1589
self.data_downlink_handler = None
1590
1591
self.last_poll_sensor = None
1592
self.last_data_time = None
1593
1594
def progress_tag(self):
1595
return "FRSkySPort"
1596
1597
def handle_data_downlink(self, some_bytes):
1598
self.progress("DOWNLINK %s" % (str(some_bytes),))
1599
if self.data_downlink_handler is not None:
1600
self.data_downlink_handler(some_bytes)
1601
self.last_data_time = self.get_time()
1602
1603
def handle_data(self, dataid, value):
1604
if dataid not in self.id_descriptions:
1605
raise KeyError("dataid 0x%02x" % dataid)
1606
self.progress("%s (0x%x)=%u" % (self.id_descriptions[dataid], dataid, value))
1607
self.data_by_id[dataid] = value
1608
if dataid not in self.dataid_counts:
1609
self.dataid_counts[dataid] = 0
1610
self.dataid_counts[dataid] += 1
1611
self.last_data_time = self.get_time()
1612
1613
def dump_dataid_counts_as_progress_messages(self):
1614
for dataid in self.dataid_counts:
1615
self.progress("0x%x: %u (%s)" % (dataid, self.dataid_counts[dataid], self.id_descriptions[dataid]))
1616
1617
def dump_sensor_id_poll_counts_as_progress_messages(self):
1618
for sensor_id in self.sensor_id_poll_counts:
1619
self.progress("(0x%x): %u" % (sensor_id, self.sensor_id_poll_counts[sensor_id]))
1620
1621
def read_bytestuffed_byte(self):
1622
b = self.buffer[0]
1623
if b == 0x7D:
1624
# byte-stuffed
1625
if len(self.buffer) < 2:
1626
self.consume = 0
1627
return None
1628
self.consume = 2
1629
b2 = self.buffer[1]
1630
if b2 == 0x5E:
1631
return self.START_STOP_SPORT
1632
if b2 == 0x5D:
1633
return self.BYTESTUFF_SPORT
1634
raise ValueError("Unknown stuffed byte (0x%02x)" % b2)
1635
return b
1636
1637
def calc_crc(self, byte):
1638
self.crc += byte
1639
self.crc += self.crc >> 8
1640
self.crc &= 0xFF
1641
1642
def next_sensor(self):
1643
ret = self.sensors_to_poll[self.next_sensor_id_to_poll]
1644
self.next_sensor_id_to_poll += 1
1645
if self.next_sensor_id_to_poll >= len(self.sensors_to_poll):
1646
self.next_sensor_id_to_poll = 0
1647
return ret
1648
1649
def check_poll(self):
1650
now = self.get_time()
1651
# self.progress("check poll (%u)" % now)
1652
1653
# sometimes ArduPilot will not respond to a poll - for
1654
# example, if you poll an unhealthy RPM sensor then we will
1655
# *never* get a response back. So we must re-poll (which
1656
# moves onto the next sensor):
1657
if now - self.poll_sent > 5:
1658
if self.last_poll_sensor is None:
1659
self.progress("Re-polling (last poll sensor was None)")
1660
else:
1661
msg = ("Re-polling (last_poll_sensor=0x%02x state=%s)" %
1662
(self.last_poll_sensor, self.state))
1663
self.progress(msg)
1664
if self.state != self.state_WANT_FRAME_TYPE:
1665
raise ValueError("Expected to be wanting a frame type when repolling (state=%s)" % str(self.state))
1666
self.state = self.state_SEND_POLL
1667
1668
if self.state == self.state_SEND_POLL:
1669
sensor_id = self.next_sensor()
1670
self.progress("Sending poll for 0x%02x" % sensor_id)
1671
self.last_poll_sensor = sensor_id
1672
if sensor_id not in self.sensor_id_poll_counts:
1673
self.sensor_id_poll_counts[sensor_id] = 0
1674
self.sensor_id_poll_counts[sensor_id] += 1
1675
packet = SPortPollPacket(sensor_id)
1676
self.send_sport_packet(packet)
1677
self.state = self.state_WANT_FRAME_TYPE
1678
self.poll_sent = now
1679
1680
def send_sport_packets(self, packets):
1681
for packet in packets:
1682
self.send_sport_packet(packet)
1683
1684
def send_sport_packet(self, packet):
1685
stuffed = packet.for_wire()
1686
self.progress("Sending (%s) (%u)" %
1687
(["0x%02x" % x for x in bytearray(stuffed)], len(stuffed)))
1688
self.port.sendall(stuffed)
1689
1690
def send_mavlite_param_request_read(self, parameter_name):
1691
mavlite_msg = MAVliteMessage(
1692
mavutil.mavlink.MAVLINK_MSG_ID_PARAM_REQUEST_READ,
1693
bytearray(parameter_name.encode())
1694
)
1695
1696
packets = mavlite_msg.to_sport_packets()
1697
1698
self.send_sport_packets(packets)
1699
1700
def send_mavlite_param_set(self, parameter_name, value):
1701
out = bytearray(struct.pack("<f", value))
1702
out.extend(parameter_name.encode())
1703
1704
mavlite_msg = MAVliteMessage(
1705
mavutil.mavlink.MAVLINK_MSG_ID_PARAM_SET,
1706
out
1707
)
1708
1709
packets = mavlite_msg.to_sport_packets()
1710
1711
self.send_sport_packets(packets)
1712
1713
def send_mavlite_command_long(
1714
self,
1715
command,
1716
p1=None,
1717
p2=None,
1718
p3=None,
1719
p4=None,
1720
p5=None,
1721
p6=None,
1722
p7=None,
1723
):
1724
params = bytearray()
1725
seen_none = False
1726
for p in p1, p2, p3, p4, p5, p6, p7:
1727
if p is None:
1728
seen_none = True
1729
continue
1730
if seen_none:
1731
raise ValueError("Can't have values after Nones!")
1732
params.extend(bytearray(struct.pack("<f", p)))
1733
1734
out = bytearray(struct.pack("<H", command)) # first two bytes are command-id
1735
options = len(params) // 4 # low-three-bits is parameter count
1736
out.extend(bytearray(struct.pack("<B", options))) # second byte is options
1737
out.extend(params) # then the float values
1738
1739
mavlite_msg = MAVliteMessage(
1740
mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_LONG,
1741
out
1742
)
1743
1744
packets = mavlite_msg.to_sport_packets()
1745
1746
self.send_sport_packets(packets)
1747
1748
def update(self):
1749
if not self.connected:
1750
if not self.connect():
1751
self.progress("Failed to connect")
1752
return
1753
self.do_sport_read()
1754
self.check_poll()
1755
1756
def do_sport_read(self):
1757
self.buffer += self.do_read()
1758
self.consume = None
1759
while len(self.buffer):
1760
if self.consume is not None:
1761
self.buffer = self.buffer[self.consume:]
1762
if len(self.buffer) == 0:
1763
break
1764
self.consume = 1
1765
b = self.buffer[0]
1766
# self.progress("Have (%s) bytes state=%s b=0x%02x" % (str(len(self.buffer)), str(self.state), b));
1767
if self.state == self.state_WANT_FRAME_TYPE:
1768
if b in [self.SPORT_DATA_FRAME, self.SPORT_DOWNLINK_FRAME]:
1769
self.frame = b
1770
self.crc = 0
1771
self.calc_crc(b)
1772
self.state = self.state_WANT_ID1
1773
continue
1774
# we may come into a stream mid-way, so we can't judge
1775
self.progress("############# Bad char %x" % b)
1776
raise ValueError("Bad char (0x%02x)" % b)
1777
self.bad_chars += 1
1778
continue
1779
elif self.state == self.state_WANT_ID1:
1780
self.id1 = self.read_bytestuffed_byte()
1781
if self.id1 is None:
1782
break
1783
self.calc_crc(self.id1)
1784
self.state = self.state_WANT_ID2
1785
continue
1786
elif self.state == self.state_WANT_ID2:
1787
self.id2 = self.read_bytestuffed_byte()
1788
if self.id2 is None:
1789
break
1790
self.calc_crc(self.id2)
1791
self.state = self.state_WANT_DATA
1792
self.data_bytes = []
1793
self.data = 0
1794
continue
1795
elif self.state == self.state_WANT_DATA:
1796
data_byte = self.read_bytestuffed_byte()
1797
if data_byte is None:
1798
break
1799
self.calc_crc(data_byte)
1800
self.data = self.data | (data_byte << (8*(len(self.data_bytes))))
1801
self.data_bytes.append(data_byte)
1802
if len(self.data_bytes) == 4:
1803
self.state = self.state_WANT_CRC
1804
continue
1805
elif self.state == self.state_WANT_CRC:
1806
crc = self.read_bytestuffed_byte()
1807
if crc is None:
1808
break
1809
self.crc = 0xFF - self.crc
1810
dataid = (self.id2 << 8) | self.id1
1811
if self.crc != crc:
1812
self.progress("Incorrect frsky checksum (received=%02x calculated=%02x id=0x%x)" % (crc, self.crc, dataid))
1813
# raise ValueError("Incorrect frsky checksum (want=%02x got=%02x id=0x%x)" % (crc, self.crc, dataid))
1814
else:
1815
if self.frame == self.SPORT_DOWNLINK_FRAME:
1816
self.handle_data_downlink([
1817
self.id1,
1818
self.id2,
1819
self.data_bytes[0],
1820
self.data_bytes[1],
1821
self.data_bytes[2],
1822
self.data_bytes[3]]
1823
)
1824
else:
1825
self.handle_data(dataid, self.data)
1826
self.state = self.state_SEND_POLL
1827
elif self.state == self.state_SEND_POLL:
1828
# this is done in check_poll
1829
self.progress("in send_poll state")
1830
pass
1831
else:
1832
raise ValueError("Unknown state (%s)" % self.state)
1833
1834
def get_data(self, dataid):
1835
try:
1836
return self.data_by_id[dataid]
1837
except KeyError:
1838
pass
1839
return None
1840
1841
1842
class FRSkyPassThrough(FRSkySPort):
1843
def __init__(self, destination_address, get_time=time.time):
1844
super(FRSkyPassThrough, self).__init__(destination_address,
1845
get_time=get_time)
1846
1847
self.sensors_to_poll = [self.SENSOR_ID_27]
1848
1849
def progress_tag(self):
1850
return "FRSkyPassthrough"
1851
1852
1853
class LocationInt(object):
1854
def __init__(self, lat, lon, alt, yaw):
1855
self.lat = lat
1856
self.lon = lon
1857
self.alt = alt
1858
self.yaw = yaw
1859
1860
1861
class Test(object):
1862
'''a test definition - information about a test'''
1863
def __init__(self, function, kwargs: dict | None = None, attempts=1, speedup=None):
1864
if kwargs is None:
1865
kwargs = {}
1866
self.name = function.__name__
1867
self.description = function.__doc__
1868
if self.description is None:
1869
raise ValueError("%s is missing a docstring" % self.name)
1870
self.function = function
1871
self.kwargs = kwargs
1872
self.attempts = attempts
1873
self.speedup = speedup
1874
1875
1876
class Result(object):
1877
'''a test result - pass, fail, exception, runtime, ....'''
1878
def __init__(self, test):
1879
self.test = test
1880
self.reason = None
1881
self.exception = None
1882
self.debug_filename = None
1883
self.time_elapsed = 0.0
1884
# self.passed = False
1885
1886
def __str__(self):
1887
ret = " %s (%s)" % (self.test.name, self.test.description)
1888
if self.passed:
1889
return f"{ret} OK"
1890
if self.reason is not None:
1891
ret += f" ({self.reason} )"
1892
if self.exception is not None:
1893
ret += f" ({str(self.exception)})"
1894
if self.debug_filename is not None:
1895
ret += f" (see {self.debug_filename})"
1896
if self.time_elapsed is not None:
1897
ret += f" (duration {self.time_elapsed} s)"
1898
return ret
1899
1900
1901
class ValgrindFailedResult(Result):
1902
'''a custom Result to allow passing of Vaglrind failures around'''
1903
def __init__(self):
1904
super(ValgrindFailedResult, self).__init__(None)
1905
self.passed = False
1906
1907
def __str__(self):
1908
return "Valgrind error detected"
1909
1910
1911
class TestSuite(abc.ABC):
1912
"""Base abstract class.
1913
It implements the common function for all vehicle types.
1914
"""
1915
def __init__(self,
1916
binary,
1917
valgrind=False,
1918
callgrind=False,
1919
gdb=False,
1920
gdb_no_tui=False,
1921
speedup=None,
1922
frame=None,
1923
params=None,
1924
gdbserver=False,
1925
lldb=False,
1926
strace=False,
1927
breakpoints: list | None = None,
1928
disable_breakpoints=False,
1929
viewerip=None,
1930
use_map=False,
1931
_show_test_timings=False,
1932
logs_dir=None,
1933
force_ahrs_type=None,
1934
replay=False,
1935
sup_binaries: list | None = None,
1936
reset_after_every_test=False,
1937
force_32bit=False,
1938
ubsan=False,
1939
ubsan_abort=False,
1940
num_aux_imus=0,
1941
dronecan_tests=False,
1942
generate_junit=False,
1943
build_opts: dict | None = None,
1944
enable_fgview=False,
1945
move_logs_on_test_failure: bool = False,
1946
):
1947
if breakpoints is None:
1948
breakpoints = []
1949
if sup_binaries is None:
1950
sup_binaries = []
1951
if build_opts is None:
1952
build_opts = {}
1953
1954
self.start_time = time.time()
1955
1956
if binary is None:
1957
raise ValueError("Should always have a binary")
1958
1959
self.binary = binary
1960
self.valgrind = valgrind
1961
self.callgrind = callgrind
1962
self.gdb = gdb
1963
self.gdb_no_tui = gdb_no_tui
1964
self.lldb = lldb
1965
self.strace = strace
1966
self.frame = frame
1967
self.params = params
1968
self.gdbserver = gdbserver
1969
self.breakpoints = breakpoints
1970
self.disable_breakpoints = disable_breakpoints
1971
self.speedup = speedup
1972
if self.speedup is None:
1973
self.speedup = self.default_speedup()
1974
self.sup_binaries = sup_binaries
1975
self.reset_after_every_test = reset_after_every_test
1976
self.force_32bit = force_32bit
1977
self.ubsan = ubsan
1978
self.ubsan_abort = ubsan_abort
1979
self.build_opts = build_opts
1980
self.move_logs_on_test_failure = move_logs_on_test_failure
1981
self.num_aux_imus = num_aux_imus
1982
self.generate_junit = generate_junit
1983
if generate_junit:
1984
try:
1985
spec = importlib.util.find_spec("junitparser")
1986
if spec is None:
1987
raise ImportError
1988
except ImportError as e:
1989
raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python3 -m pip install junitparser")
1990
1991
self.mavproxy = None
1992
self._mavproxy = None # for auto-cleanup on failed tests
1993
self.mav = None
1994
self.viewerip = viewerip
1995
self.use_map = use_map
1996
self.contexts = []
1997
self.context_push()
1998
self.buildlog = None
1999
self.copy_tlog = False
2000
self.logfile = None
2001
self.max_set_rc_timeout = 0
2002
self.last_wp_load = 0
2003
self.forced_post_test_sitl_reboots = 0
2004
self.run_tests_called = False
2005
self._show_test_timings = _show_test_timings
2006
self.test_timings = dict()
2007
self.total_waiting_to_arm_time = 0
2008
self.waiting_to_arm_count = 0
2009
self.force_ahrs_type = force_ahrs_type
2010
self.replay = replay
2011
if self.force_ahrs_type is not None:
2012
self.force_ahrs_type = int(self.force_ahrs_type)
2013
self.logs_dir = logs_dir
2014
self.timesync_number = 137
2015
self.last_progress_sent_as_statustext = None
2016
self.last_heartbeat_time_ms = None
2017
self.last_heartbeat_time_wc_s = 0
2018
self.in_drain_mav = False
2019
self.tlog = None
2020
self.enable_fgview = enable_fgview
2021
2022
self.rc_thread = None
2023
self.rc_thread_should_quit = False
2024
self.rc_queue = Queue.Queue()
2025
2026
self.expect_list = []
2027
2028
self.start_mavproxy_count = 0
2029
2030
self.last_sim_time_cached = 0
2031
self.last_sim_time_cached_wallclock = 0
2032
2033
# to autotest we do not want to go to the internet for tiles,
2034
# usually. Set this to False to gather tiles from internet in
2035
# the case there are new tiles required, then add them to the
2036
# repo and set this back to false:
2037
# the files will likely be downloaded to ~/.tilecache/SRTM3
2038
self.terrain_in_offline_mode = True
2039
self.elevationmodel = mp_elevation.ElevationModel(
2040
cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"),
2041
offline=self.terrain_in_offline_mode
2042
)
2043
self.terrain_data_messages_sent = 0 # count of messages back
2044
self.dronecan_tests = dronecan_tests
2045
self.statustext_id = 1
2046
self.message_hooks = [] # functions or MessageHook instances
2047
2048
def __del__(self):
2049
if self.rc_thread is not None:
2050
self.progress("Joining RC thread in __del__")
2051
self.rc_thread_should_quit = True
2052
self.rc_thread.join()
2053
self.rc_thread = None
2054
2055
def default_speedup(self):
2056
return 8
2057
2058
def progress(self, text, send_statustext=True):
2059
"""Display autotest progress text."""
2060
delta_time = time.time() - self.start_time
2061
formatted_text = "AT-%06.1f: %s" % (delta_time, text)
2062
print(formatted_text)
2063
if (send_statustext and
2064
self.mav is not None and
2065
self.mav.port is not None and
2066
self.last_progress_sent_as_statustext != text):
2067
self.send_statustext(formatted_text)
2068
self.last_progress_sent_as_statustext = text
2069
2070
# following two functions swiped from autotest.py:
2071
@staticmethod
2072
def buildlogs_dirpath():
2073
return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
2074
2075
def sitl_home(self):
2076
HOME = self.sitl_start_location()
2077
return "%f,%f,%u,%u" % (HOME.lat,
2078
HOME.lng,
2079
HOME.alt,
2080
HOME.heading)
2081
2082
def mavproxy_version(self):
2083
'''return the current version of mavproxy as a tuple e.g. (1,8,8)'''
2084
return util.MAVProxy_version()
2085
2086
def mavproxy_version_gt(self, major, minor, point):
2087
if os.getenv("AUTOTEST_FORCE_MAVPROXY_VERSION", None) is not None:
2088
return True
2089
(got_major, got_minor, got_point) = self.mavproxy_version()
2090
self.progress("Got: %s.%s.%s" % (got_major, got_minor, got_point))
2091
if got_major > major:
2092
return True
2093
elif got_major < major:
2094
return False
2095
if got_minor > minor:
2096
return True
2097
elif got_minor < minor:
2098
return False
2099
return got_point > point
2100
2101
def open_mavproxy_logfile(self):
2102
return MAVProxyLogFile()
2103
2104
def buildlogs_path(self, path):
2105
"""Return a string representing path in the buildlogs directory."""
2106
bits = [self.buildlogs_dirpath()]
2107
if isinstance(path, list):
2108
bits.extend(path)
2109
else:
2110
bits.append(path)
2111
return os.path.join(*bits)
2112
2113
def sitl_streamrate(self):
2114
"""Allow subclasses to override SITL streamrate."""
2115
return 10
2116
2117
def adjust_ardupilot_port(self, port):
2118
'''adjust port in case we do not wish to use the default range (5760 and 5501 etc)'''
2119
return port
2120
2121
def spare_network_port(self, offset=0):
2122
'''returns a network port which should be able to be bound'''
2123
if offset > 2:
2124
raise ValueError("offset too large")
2125
return 8000 + offset
2126
2127
def autotest_connection_string_to_ardupilot(self):
2128
return "tcp:127.0.0.1:%u" % self.adjust_ardupilot_port(5760)
2129
2130
def sitl_rcin_port(self, offset=0):
2131
if offset > 2:
2132
raise ValueError("offset too large")
2133
return 5501 + offset
2134
2135
def mavproxy_options(self):
2136
"""Returns options to be passed to MAVProxy."""
2137
ret = [
2138
'--streamrate=%u' % self.sitl_streamrate(),
2139
'--target-system=%u' % self.sysid_thismav(),
2140
'--target-component=1',
2141
]
2142
if self.viewerip:
2143
ret.append("--out=%s:14550" % self.viewerip)
2144
if self.use_map:
2145
ret.append('--map')
2146
2147
return ret
2148
2149
def vehicleinfo_key(self):
2150
return self.log_name()
2151
2152
def repeatedly_apply_parameter_filepath(self, filepath):
2153
if False:
2154
return self.repeatedly_apply_parameter_filepath_mavproxy(filepath)
2155
parameters = mavparm.MAVParmDict()
2156
# correct_parameters = set()
2157
if not parameters.load(filepath):
2158
raise ValueError("Param load failed")
2159
param_dict = {}
2160
for p in parameters.keys():
2161
param_dict[p] = parameters[p]
2162
self.set_parameters(param_dict)
2163
2164
def repeatedly_apply_parameter_filepath_mavproxy(self, filepath):
2165
'''keep applying a parameter file until no parameters changed'''
2166
for i in range(0, 3):
2167
self.mavproxy.send("param load %s\n" % filepath)
2168
while True:
2169
line = self.mavproxy.readline()
2170
match = re.match(".*Loaded [0-9]+ parameters.*changed ([0-9]+)",
2171
line)
2172
if match is not None:
2173
if int(match.group(1)) == 0:
2174
return
2175
break
2176
raise NotAchievedException()
2177
2178
def apply_defaultfile_parameters(self):
2179
"""Apply parameter file."""
2180
self.progress("Applying default parameters file")
2181
# setup test parameters
2182
if self.params is None:
2183
self.params = self.model_defaults_filepath(self.frame)
2184
for x in self.params:
2185
self.repeatedly_apply_parameter_filepath(x)
2186
2187
def count_lines_in_filepath(self, filepath):
2188
return len([i for i in open(filepath)])
2189
2190
def count_expected_fence_lines_in_filepath(self, filepath):
2191
count = 0
2192
is_qgc = False
2193
for i in open(filepath):
2194
i = re.sub("#.*", "", i) # trim comments
2195
if i.isspace():
2196
# skip empty lines
2197
continue
2198
if re.match("QGC", i):
2199
# skip QGC header line
2200
is_qgc = True
2201
continue
2202
count += 1
2203
if is_qgc:
2204
count += 2 # file doesn't include return point + closing point
2205
return count
2206
2207
def load_fence_using_mavproxy(self, mavproxy, filename):
2208
self.set_parameter("FENCE_TOTAL", 0)
2209
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2210
count = self.count_expected_fence_lines_in_filepath(filepath)
2211
mavproxy.send('fence load %s\n' % filepath)
2212
# self.mavproxy.expect("Loaded %u (geo-)?fence" % count)
2213
self.wait_parameter_value("FENCE_TOTAL", count, timeout=20)
2214
2215
def get_fence_point(self, idx, target_system=1, target_component=1):
2216
self.mav.mav.fence_fetch_point_send(target_system,
2217
target_component,
2218
idx)
2219
m = self.assert_receive_message("FENCE_POINT", timeout=2)
2220
self.progress("m: %s" % str(m))
2221
if m.idx != idx:
2222
raise NotAchievedException("Invalid idx returned (want=%u got=%u)" %
2223
(idx, m.seq))
2224
return m
2225
2226
def fencepoint_protocol_epsilon(self):
2227
return 0.00002
2228
2229
def roundtrip_fencepoint_protocol(self, offset, count, lat, lng, target_system=1, target_component=1):
2230
self.progress("Sending FENCE_POINT offs=%u count=%u" % (offset, count))
2231
self.mav.mav.fence_point_send(target_system,
2232
target_component,
2233
offset,
2234
count,
2235
lat,
2236
lng)
2237
2238
self.progress("Requesting fence point")
2239
m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)
2240
if abs(m.lat - lat) > self.fencepoint_protocol_epsilon():
2241
raise NotAchievedException("Did not get correct lat in fencepoint: got=%f want=%f" % (m.lat, lat))
2242
if abs(m.lng - lng) > self.fencepoint_protocol_epsilon():
2243
raise NotAchievedException("Did not get correct lng in fencepoint: got=%f want=%f" % (m.lng, lng))
2244
self.progress("Roundtrip OK")
2245
2246
def roundtrip_fence_using_fencepoint_protocol(self, loc_list, target_system=1, target_component=1, ordering=None):
2247
count = len(loc_list)
2248
offset = 0
2249
self.set_parameter("FENCE_TOTAL", count)
2250
if ordering is None:
2251
ordering = range(count)
2252
elif len(ordering) != len(loc_list):
2253
raise ValueError("ordering list length mismatch")
2254
2255
for offset in ordering:
2256
loc = loc_list[offset]
2257
self.roundtrip_fencepoint_protocol(offset,
2258
count,
2259
loc.lat,
2260
loc.lng,
2261
target_system,
2262
target_component)
2263
2264
self.progress("Validating uploaded fence")
2265
returned_count = self.get_parameter("FENCE_TOTAL")
2266
if returned_count != count:
2267
raise NotAchievedException("Returned count mismatch (want=%u got=%u)" %
2268
(count, returned_count))
2269
for i in range(count):
2270
self.progress("Requesting fence point")
2271
m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)
2272
if abs(m.lat-loc.lat) > self.fencepoint_protocol_epsilon():
2273
raise NotAchievedException("Returned lat mismatch (want=%f got=%f" %
2274
(loc.lat, m.lat))
2275
if abs(m.lng-loc.lng) > self.fencepoint_protocol_epsilon():
2276
raise NotAchievedException("Returned lng mismatch (want=%f got=%f" %
2277
(loc.lng, m.lng))
2278
if m.count != count:
2279
raise NotAchievedException("Count mismatch (want=%u got=%u)" %
2280
(count, m.count))
2281
2282
def load_fence(self, filename):
2283
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2284
if not os.path.exists(filepath):
2285
filepath = self.generic_mission_filepath_for_filename(filename)
2286
self.progress("Loading fence from (%s)" % str(filepath))
2287
locs = []
2288
for line in open(filepath, 'rb'):
2289
if len(line) == 0:
2290
continue
2291
m = re.match(r"([-\d.]+)\s+([-\d.]+)\s*", line.decode('ascii'))
2292
if m is None:
2293
raise ValueError("Did not match (%s)" % line)
2294
locs.append(mavutil.location(float(m.group(1)), float(m.group(2)), 0, 0))
2295
if self.is_plane():
2296
# create return point as the centroid:
2297
total_lat = 0
2298
total_lng = 0
2299
total_cnt = 0
2300
for loc in locs:
2301
total_lat += loc.lat
2302
total_lng += loc.lng
2303
total_cnt += 1
2304
locs2 = [mavutil.location(total_lat/total_cnt,
2305
total_lng/total_cnt,
2306
0,
2307
0)] # return point
2308
locs2.extend(locs)
2309
locs2.append(copy.copy(locs2[1]))
2310
return self.roundtrip_fence_using_fencepoint_protocol(locs2)
2311
2312
self.upload_fences_from_locations([
2313
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),
2314
])
2315
2316
def load_fence_using_mavwp(self, filename):
2317
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2318
if not os.path.exists(filepath):
2319
filepath = self.generic_mission_filepath_for_filename(filename)
2320
self.progress("Loading fence from (%s)" % str(filepath))
2321
items = self.mission_item_protocol_items_from_filepath(mavwp.MissionItemProtocol_Fence, filepath)
2322
self.check_fence_upload_download(items)
2323
2324
def send_reboot_command(self):
2325
self.mav.mav.command_long_send(self.sysid_thismav(),
2326
1,
2327
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2328
1, # confirmation
2329
1, # reboot autopilot
2330
0,
2331
0,
2332
0,
2333
0,
2334
0,
2335
0)
2336
2337
def reboot_check_valgrind_log(self):
2338
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
2339
model=self.frame)
2340
if os.path.isfile(valgrind_log) and (os.path.getsize(valgrind_log) > 0):
2341
backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))
2342
shutil.move(valgrind_log, backup_valgrind_log)
2343
2344
def run_cmd_reboot(self):
2345
self.run_cmd_int(
2346
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2347
p1=1, # reboot autopilot
2348
)
2349
2350
def run_cmd_enable_high_latency(self, new_state, run_cmd=None):
2351
if run_cmd is None:
2352
run_cmd = self.run_cmd
2353
p1 = 0
2354
if new_state:
2355
p1 = 1
2356
2357
run_cmd(
2358
mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY,
2359
p1=p1, # enable/disable
2360
)
2361
2362
def reboot_sitl_mav(self, required_bootcount=None, force=False):
2363
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
2364
# we must make sure that stats have been reset - otherwise
2365
# when we reboot we'll reset statistics again and lose our
2366
# STAT_BOOTCNT increment:
2367
tstart = time.time()
2368
while True:
2369
if time.time() - tstart > 30:
2370
raise NotAchievedException("STAT_RESET did not go non-zero")
2371
if self.get_parameter('STAT_RESET', timeout_in_wallclock=True) != 0:
2372
break
2373
2374
old_bootcount = self.get_parameter('STAT_BOOTCNT')
2375
# ardupilot SITL may actually NAK the reboot; replace with
2376
# run_cmd when we don't do that.
2377
do_context = False
2378
if self.valgrind or self.callgrind:
2379
self.reboot_check_valgrind_log()
2380
self.progress("Stopping and restarting SITL")
2381
if getattr(self, 'valgrind_restart_customisations', None) is not None:
2382
self.customise_SITL_commandline(
2383
self.valgrind_restart_customisations,
2384
model=self.valgrind_restart_model,
2385
defaults_filepath=self.valgrind_restart_defaults_filepath,
2386
)
2387
else:
2388
self.stop_SITL()
2389
self.start_SITL(wipe=False)
2390
else:
2391
# receiving an ACK from the process turns out to be really
2392
# quite difficult. So just send it and hope for the best.
2393
self.progress("Sending reboot command")
2394
p6 = 0
2395
if force:
2396
p6 = 20190226 # magic force-reboot value
2397
self.send_cmd(
2398
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2399
p1=1,
2400
p2=1,
2401
p6=p6,
2402
)
2403
do_context = True
2404
if do_context:
2405
self.context_push()
2406
2407
def hook(mav, m):
2408
if m.get_type() != 'COMMAND_ACK':
2409
return
2410
if m.command != mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
2411
return
2412
self.progress("While awaiting reboot received (%s)" % str(m))
2413
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
2414
raise NotAchievedException("Bad reboot ACK detected")
2415
self.install_message_hook_context(hook)
2416
2417
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
2418
2419
if do_context:
2420
self.context_pop()
2421
2422
def send_cmd_enter_cpu_lockup(self):
2423
"""Poke ArduPilot to stop the main loop from running"""
2424
self.mav.mav.command_long_send(self.sysid_thismav(),
2425
1,
2426
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2427
1, # confirmation
2428
42, # lockup autopilot
2429
24, # no, really, we mean it
2430
71, # seriously, we're not kidding
2431
93, # we know exactly what we're
2432
0,
2433
0,
2434
0)
2435
2436
def reboot_sitl(self,
2437
required_bootcount=None,
2438
force=False,
2439
check_position=True,
2440
mark_context=True,
2441
startup_location_dist_max=1,
2442
):
2443
"""Reboot SITL instance and wait for it to reconnect."""
2444
if self.armed() and not force:
2445
raise NotAchievedException("Reboot attempted while armed")
2446
self.progress("Rebooting SITL")
2447
self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force)
2448
self.do_heartbeats(force=True)
2449
if check_position and self.frame != 'sailboat': # sailboats drift with wind!
2450
self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max)
2451
if mark_context:
2452
self.context_get().reboot_sitl_was_done = True
2453
2454
def assert_armed(self):
2455
if not self.armed():
2456
raise NotAchievedException("Not armed")
2457
2458
def reboot_sitl_mavproxy(self, required_bootcount=None):
2459
"""Reboot SITL instance using MAVProxy and wait for it to reconnect."""
2460
old_bootcount = self.get_parameter('STAT_BOOTCNT')
2461
self.mavproxy.send("reboot\n")
2462
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
2463
2464
def detect_and_handle_reboot(self, old_bootcount, required_bootcount=None, timeout=10):
2465
tstart = time.time()
2466
if required_bootcount is None:
2467
required_bootcount = old_bootcount + 1
2468
while True:
2469
if time.time() - tstart > timeout:
2470
raise AutoTestTimeoutException("Did not detect reboot")
2471
try:
2472
current_bootcount = self.get_parameter('STAT_BOOTCNT',
2473
timeout=1,
2474
attempts=1,
2475
verbose=True,
2476
timeout_in_wallclock=True)
2477
self.progress("current=%s required=%u" %
2478
(str(current_bootcount), required_bootcount))
2479
if current_bootcount == required_bootcount:
2480
break
2481
except NotAchievedException:
2482
pass
2483
except AutoTestTimeoutException:
2484
pass
2485
except ConnectionResetError:
2486
pass
2487
except socket.error:
2488
pass
2489
except Exception as e:
2490
self.progress("Got unexpected exception (%s)" % str(type(e)))
2491
pass
2492
2493
# empty mav to avoid getting old timestamps:
2494
self.do_timesync_roundtrip(timeout_in_wallclock=True)
2495
2496
self.progress("Calling initialise-after-reboot")
2497
self.initialise_after_reboot_sitl()
2498
2499
def scripting_restart(self):
2500
'''restart scripting subsystem'''
2501
self.progress("Restarting Scripting")
2502
self.run_cmd_int(
2503
mavutil.mavlink.MAV_CMD_SCRIPTING,
2504
p1=mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,
2505
timeout=5,
2506
)
2507
2508
def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):
2509
'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''
2510
self.do_timesync_roundtrip(timeout_in_wallclock=True)
2511
tstart = time.time()
2512
while True:
2513
if time.time() - tstart > timeout:
2514
raise NotAchievedException("Failed to set streamrate")
2515
self.mav.mav.request_data_stream_send(
2516
1,
2517
1,
2518
stream,
2519
streamrate,
2520
1)
2521
m = self.mav.recv_match(type='SYSTEM_TIME',
2522
blocking=True,
2523
timeout=1)
2524
if m is not None:
2525
break
2526
2527
def set_streamrate_mavproxy(self, streamrate, timeout=10):
2528
tstart = time.time()
2529
while True:
2530
if time.time() - tstart > timeout:
2531
raise AutoTestTimeoutException("stream rate change failed")
2532
2533
self.mavproxy.send("set streamrate %u\n" % (streamrate))
2534
self.mavproxy.send("set streamrate\n")
2535
try:
2536
self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1)
2537
except pexpect.TIMEOUT:
2538
continue
2539
rate = self.mavproxy.match.group(1)
2540
# self.progress("rate: %s" % str(rate))
2541
if int(rate) == int(streamrate):
2542
break
2543
2544
if streamrate <= 0:
2545
return
2546
2547
self.progress("Waiting for SYSTEM_TIME for confirmation streams are working")
2548
self.drain_mav_unparsed()
2549
timeout = 60
2550
tstart = time.time()
2551
while True:
2552
self.drain_all_pexpects()
2553
if time.time() - tstart > timeout:
2554
raise NotAchievedException("Did not get SYSTEM_TIME within %f seconds" % timeout)
2555
m = self.mav.recv_match(timeout=0.1)
2556
if m is None:
2557
continue
2558
# self.progress("Received (%s)" % str(m))
2559
if m.get_type() == 'SYSTEM_TIME':
2560
break
2561
self.drain_mav()
2562
2563
def htree_from_xml(self, xml_filepath):
2564
'''swiped from mavproxy_param.py'''
2565
xml = open(xml_filepath, 'rb').read()
2566
from lxml import objectify
2567
objectify.enable_recursive_str()
2568
tree = objectify.fromstring(xml)
2569
htree = {}
2570
for p in tree.vehicles.parameters.param:
2571
n = p.get('name').split(':')[1]
2572
htree[n] = p
2573
for lib in tree.libraries.parameters:
2574
for p in lib.param:
2575
n = p.get('name')
2576
htree[n] = p
2577
return htree
2578
2579
def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None):
2580
self.progress("Sending ABSD_VEHICLE message")
2581
new = here
2582
if offset_ne is not None:
2583
new = self.offset_location_ne(new, offset_ne[0], offset_ne[1])
2584
self.mav.mav.adsb_vehicle_send(
2585
37, # ICAO address
2586
int(new.lat * 1e7),
2587
int(new.lng * 1e7),
2588
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
2589
int(here.alt*1000 + 10000), # 10m up
2590
0, # heading in cdeg
2591
0, # horizontal velocity cm/s
2592
0, # vertical velocity cm/s
2593
"bob".encode("ascii"), # callsign
2594
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
2595
1, # time since last communication
2596
65535, # flags
2597
17 # squawk
2598
)
2599
2600
def test_parameter_documentation_get_all_parameters(self):
2601
2602
xml_filepath = os.path.join(self.buildlogs_dirpath(), "apm.pdef.xml")
2603
param_parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'param_metadata', 'param_parse.py')
2604
try:
2605
os.unlink(xml_filepath)
2606
except OSError:
2607
pass
2608
vehicle = self.log_name()
2609
if vehicle == "HeliCopter":
2610
vehicle = "ArduCopter"
2611
if vehicle == "QuadPlane":
2612
vehicle = "ArduPlane"
2613
cmd = [param_parse_filepath, '--vehicle', vehicle]
2614
# cmd.append("--verbose")
2615
if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:
2616
self.progress("Failed param_parse.py (%s)" % vehicle)
2617
return False
2618
htree = self.htree_from_xml(xml_filepath)
2619
2620
target_system = self.sysid_thismav()
2621
target_component = 1
2622
2623
self.customise_SITL_commandline([
2624
"--unhide-groups"
2625
])
2626
2627
(parameters, seq_id) = self.download_parameters(target_system, target_component)
2628
2629
self.reset_SITL_commandline()
2630
2631
fail = False
2632
for param in parameters.keys():
2633
if param not in htree:
2634
self.progress("%s not in XML" % param)
2635
fail = True
2636
if fail:
2637
raise NotAchievedException("Downloaded parameters missing in XML")
2638
2639
# FIXME: this should be doable if we filter out e.g BRD_* and CAN_*?
2640
# self.progress("Checking no extra parameters present in XML")
2641
# fail = False
2642
# for param in htree:
2643
# if param.startswith("SIM_"):
2644
# # too many of these to worry about
2645
# continue
2646
# if param not in parameters:
2647
# print("%s not in downloaded parameters but in XML" % param)
2648
# fail = True
2649
# if fail:
2650
# raise NotAchievedException("Extra parameters in XML")
2651
2652
def find_format_defines(self, lines):
2653
ret = {}
2654
for line in lines:
2655
if isinstance(line, bytes):
2656
line = line.decode("utf-8")
2657
m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)
2658
if m is None:
2659
continue
2660
(a, b) = (m.group(1), m.group(2))
2661
if a in ret:
2662
raise NotAchievedException("Duplicate define for (%s)" % a)
2663
ret[a] = b
2664
return ret
2665
2666
def vehicle_code_dirpath(self):
2667
'''returns path to vehicle-specific code directory e.g. ~/ardupilot/Rover'''
2668
dirname = self.log_name()
2669
if dirname == "QuadPlane":
2670
dirname = "ArduPlane"
2671
elif dirname == "HeliCopter":
2672
dirname = "ArduCopter"
2673
return os.path.join(self.rootdir(), dirname)
2674
2675
def find_LogStructureFiles(self):
2676
'''return list of files named LogStructure.h'''
2677
ret = []
2678
for root, _, files in os.walk(self.rootdir()):
2679
for f in files:
2680
if f == 'LogStructure.h':
2681
ret.append(os.path.join(root, f))
2682
if f == 'LogStructure_SBP.h':
2683
ret.append(os.path.join(root, f))
2684
return ret
2685
2686
def all_log_format_ids(self):
2687
'''parse C++ code to extract definitions of log messages'''
2688
structure_files = self.find_LogStructureFiles()
2689
structure_lines = []
2690
for f in structure_files:
2691
structure_lines.extend(open(f).readlines())
2692
2693
defines = self.find_format_defines(structure_lines)
2694
2695
ids = {}
2696
message_infos = []
2697
for f in structure_files:
2698
self.progress("structure file: %s" % f)
2699
state_outside = 0
2700
state_inside = 1
2701
state = state_outside
2702
2703
linestate_none = 45
2704
linestate_within = 46
2705
linestate = linestate_none
2706
debug = False
2707
if f == "/home/pbarker/rc/ardupilot/libraries/AP_HAL_ChibiOS/LogStructure.h":
2708
debug = True
2709
for line in open(f).readlines():
2710
if debug:
2711
print("line: %s" % line)
2712
if isinstance(line, bytes):
2713
line = line.decode("utf-8")
2714
line = re.sub("//.*", "", line) # trim comments
2715
if re.match(r"\s*$", line):
2716
# blank line
2717
continue
2718
if state == state_outside:
2719
if ("#define LOG_COMMON_STRUCTURES" in line or
2720
re.match("#define LOG_STRUCTURE_FROM_.*", line) or
2721
re.match("#define LOG_RTC_MESSAGE.*", line)):
2722
if debug:
2723
self.progress("Moving inside")
2724
state = state_inside
2725
continue
2726
if state == state_inside:
2727
if linestate == linestate_none:
2728
allowed_list = [
2729
'LOG_STRUCTURE_FROM_',
2730
'LOG_RTC_MESSAGE',
2731
]
2732
2733
allowed = False
2734
for a in allowed_list:
2735
if a in line:
2736
allowed = True
2737
if allowed:
2738
continue
2739
m = re.match(r"\s*{(.*)},\s*", line)
2740
if m is not None:
2741
# complete line
2742
if debug:
2743
print("Complete line: %s" % str(line))
2744
message_infos.append(m.group(1))
2745
continue
2746
m = re.match(r"\s*{(.*)\\", line)
2747
if m is None:
2748
if debug:
2749
self.progress("Moving outside")
2750
state = state_outside
2751
continue
2752
partial_line = m.group(1)
2753
if debug:
2754
self.progress("partial line")
2755
linestate = linestate_within
2756
continue
2757
if linestate == linestate_within:
2758
if debug:
2759
self.progress("Looking for close-brace")
2760
m = re.match("(.*)}", line)
2761
if m is None:
2762
if debug:
2763
self.progress("no close-brace")
2764
line = line.rstrip()
2765
newline = re.sub(r"\\$", "", line)
2766
if newline == line:
2767
raise NotAchievedException("Expected backslash at end of line")
2768
line = newline
2769
line = line.rstrip()
2770
# cpp-style string concatenation:
2771
if debug:
2772
self.progress("more partial line")
2773
line = re.sub(r'"\s*"', '', line)
2774
partial_line += line
2775
continue
2776
if debug:
2777
self.progress("found close-brace")
2778
message_infos.append(partial_line + m.group(1))
2779
linestate = linestate_none
2780
continue
2781
raise NotAchievedException("Bad line (%s)")
2782
2783
if linestate != linestate_none:
2784
raise NotAchievedException("Must be linestate-none at end of file")
2785
2786
# now look in the vehicle-specific logfile:
2787
filepath = os.path.join(self.vehicle_code_dirpath(), "Log.cpp")
2788
state_outside = 67
2789
state_inside = 68
2790
state = state_outside
2791
linestate_none = 89
2792
linestate_within = 90
2793
linestate = linestate_none
2794
for line in open(filepath, 'rb').readlines():
2795
if isinstance(line, bytes):
2796
line = line.decode("utf-8")
2797
line = re.sub("//.*", "", line) # trim comments
2798
if re.match(r"\s*$", line):
2799
# blank line
2800
continue
2801
if state == state_outside:
2802
if ("const LogStructure" in line or
2803
"const struct LogStructure" in line):
2804
state = state_inside
2805
continue
2806
if state == state_inside:
2807
if re.match("};", line):
2808
state = state_outside
2809
break
2810
if linestate == linestate_none:
2811
if "#if HAL_QUADPLANE_ENABLED" in line:
2812
continue
2813
if "#if FRAME_CONFIG == HELI_FRAME" in line:
2814
continue
2815
if "#if AC_PRECLAND_ENABLED" in line:
2816
continue
2817
if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line:
2818
continue
2819
if "#end" in line:
2820
continue
2821
if "LOG_COMMON_STRUCTURES" in line:
2822
continue
2823
m = re.match(r"\s*{(.*)},\s*", line)
2824
if m is not None:
2825
# complete line
2826
# print("Complete line: %s" % str(line))
2827
message_infos.append(m.group(1))
2828
continue
2829
m = re.match(r"\s*{(.*)", line)
2830
if m is None:
2831
raise NotAchievedException("Bad line %s" % line)
2832
partial_line = m.group(1)
2833
linestate = linestate_within
2834
continue
2835
if linestate == linestate_within:
2836
m = re.match("(.*)}", line)
2837
if m is None:
2838
line = line.rstrip()
2839
newline = re.sub(r"\\$", "", line)
2840
if newline == line:
2841
raise NotAchievedException("Expected backslash at end of line")
2842
line = newline
2843
line = line.rstrip()
2844
# cpp-style string concatenation:
2845
line = re.sub(r'"\s*"', '', line)
2846
partial_line += line
2847
continue
2848
message_infos.append(partial_line + m.group(1))
2849
linestate = linestate_none
2850
continue
2851
raise NotAchievedException("Bad line (%s)")
2852
2853
if state == state_inside:
2854
raise NotAchievedException("Should not be in state_inside at end")
2855
2856
for message_info in message_infos:
2857
print("message_info: %s" % str(message_info))
2858
for define in defines:
2859
message_info = re.sub(define, defines[define], message_info)
2860
m = re.match(r'\s*LOG_\w+\s*,\s*(?:sizeof|RLOG_SIZE)\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*(true|false))?\s*$', message_info) # noqa
2861
if m is None:
2862
print("NO MATCH")
2863
continue
2864
(name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5))
2865
if name in ids:
2866
raise NotAchievedException("Already seen a (%s) message" % name)
2867
ids[name] = {
2868
"name": name,
2869
"format": fmt,
2870
"labels": labels,
2871
"units": units,
2872
"multipliers": multipliers,
2873
}
2874
2875
# now look for Log_Write(...) messages:
2876
base_directories = [
2877
os.path.join(self.rootdir(), 'libraries'),
2878
self.vehicle_code_dirpath(),
2879
]
2880
log_write_statements = []
2881
for base_directory in base_directories:
2882
for root, dirs, files in os.walk(base_directory):
2883
state_outside = 37
2884
state_inside = 38
2885
state = state_outside
2886
for f in files:
2887
if not re.search("[.]cpp$", f):
2888
continue
2889
filepath = os.path.join(root, f)
2890
if "AP_Logger/examples" in filepath:
2891
# this is the sample file which contains examples...
2892
continue
2893
count = 0
2894
for line in open(filepath, 'rb').readlines():
2895
if isinstance(line, bytes):
2896
line = line.decode("utf-8")
2897
if state == state_outside:
2898
if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or
2899
re.match(r"\s*logger[.]Write(?:Streaming)?\(", line)):
2900
state = state_inside
2901
line = re.sub("//.*", "", line) # trim comments
2902
log_write_statement = line
2903
continue
2904
if state == state_inside:
2905
line = re.sub("//.*", "", line) # trim comments
2906
# cpp-style string concatenation:
2907
line = re.sub(r'"\s*"', '', line)
2908
log_write_statement += line
2909
if re.match(r".*\);", line):
2910
log_write_statements.append(log_write_statement)
2911
state = state_outside
2912
count += 1
2913
if state != state_outside:
2914
raise NotAchievedException("Expected to be outside at end of file")
2915
# print("%s has %u lines" % (f, count))
2916
# change all whitespace to single space
2917
log_write_statements = [re.sub(r"\s+", " ", x) for x in log_write_statements]
2918
# print("Got log-write-statements: %s" % str(log_write_statements))
2919
results = []
2920
for log_write_statement in log_write_statements:
2921
for define in defines:
2922
log_write_statement = re.sub(define, defines[define], log_write_statement)
2923
# fair warning: order is important here because of the
2924
# NKT/XKT special case below....
2925
my_re = r' logger[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
2926
m = re.match(my_re, log_write_statement)
2927
if m is None:
2928
my_re = r' AP::logger\(\)[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
2929
m = re.match(my_re, log_write_statement)
2930
if m is None:
2931
raise NotAchievedException("Did not match (%s) with (%s)" % (log_write_statement, str(my_re)))
2932
else:
2933
results.append((m.group(1), m.group(2)))
2934
2935
for result in results:
2936
(name, labels) = result
2937
if name in ids:
2938
raise Exception("Already have id for (%s)" % name)
2939
# self.progress("Adding Log_Write result (%s)" % name)
2940
ids[name] = {
2941
"name": name,
2942
"labels": labels,
2943
}
2944
2945
if len(ids) == 0:
2946
raise NotAchievedException("Did not get any ids")
2947
2948
return ids
2949
2950
def LoggerDocumentation_whitelist(self):
2951
'''returns a set of messages which we do not want to see
2952
documentation for'''
2953
2954
ret = set()
2955
2956
# messages not expected to be on particular vehicles. Nothing
2957
# needs fixing below this point, unless you can come up with a
2958
# better way to avoid this list!
2959
2960
# We extract all message that need to be documented from the
2961
# code, but we don't pay attention to which vehicles will use
2962
# those messages. We *do* care about the documented messages
2963
# for a vehicle as we follow the tree created by the
2964
# documentation (eg. @Path:
2965
# ../libraries/AP_LandingGear/AP_LandingGear.cpp). The lists
2966
# here have been created to fix this discrepancy.
2967
vinfo_key = self.vehicleinfo_key()
2968
if vinfo_key != 'ArduPlane' and vinfo_key != 'ArduCopter' and vinfo_key != 'Helicopter':
2969
ret.update([
2970
"ATUN", # Plane and Copter have ATUN messages
2971
])
2972
if vinfo_key != 'ArduPlane':
2973
ret.update([
2974
"TECS", # only Plane has TECS
2975
"TEC2", # only Plane has TECS
2976
"TEC3", # only Plane has TECS
2977
"TEC4", # only Plane has TECS
2978
"SOAR", # only Planes can truly soar
2979
"SORC", # soaring is pure magic
2980
"QBRK", # quadplane
2981
"FWDT", # quadplane
2982
"VAR", # variometer only applicable on Plane
2983
])
2984
if vinfo_key != 'ArduCopter' and vinfo_key != "Helicopter":
2985
ret.update([
2986
"ARHS", # autorotation
2987
"AROT", # autorotation
2988
"ARSC", # autorotation
2989
"ATDH", # heli autotune
2990
"ATNH", # heli autotune
2991
"ATSH", # heli autotune
2992
"GMB1", # sologimbal
2993
"GMB2", # sologimbal
2994
"SURF", # surface-tracking
2995
])
2996
# end not-expected-to-be-fixed block
2997
2998
return ret
2999
3000
def LoggerDocumentation(self):
3001
'''Test Onboard Logging Generation'''
3002
xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml")
3003
parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py')
3004
try:
3005
os.unlink(xml_filepath)
3006
except OSError:
3007
pass
3008
vehicle = self.log_name()
3009
if vehicle == 'BalanceBot':
3010
# same binary and parameters as Rover
3011
return
3012
vehicle_map = {
3013
"ArduCopter": "Copter",
3014
"HeliCopter": "Copter",
3015
"ArduPlane": "Plane",
3016
"QuadPlane": "Plane",
3017
"Rover": "Rover",
3018
"AntennaTracker": "Tracker",
3019
"ArduSub": "Sub",
3020
}
3021
vehicle = vehicle_map[vehicle]
3022
3023
cmd = [parse_filepath, '--vehicle', vehicle]
3024
# cmd.append("--verbose")
3025
if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:
3026
self.progress("Failed parse.py (%s)" % vehicle)
3027
return False
3028
length = os.path.getsize(xml_filepath)
3029
min_length = 1024
3030
if length < min_length:
3031
raise NotAchievedException("short xml file (%u < %u)" %
3032
(length, min_length))
3033
self.progress("xml file length is %u" % length)
3034
3035
from lxml import objectify
3036
xml = open(xml_filepath, 'rb').read()
3037
objectify.enable_recursive_str()
3038
tree = objectify.fromstring(xml)
3039
3040
whitelist = self.LoggerDocumentation_whitelist()
3041
3042
docco_ids = {}
3043
for thing in tree.logformat:
3044
name = str(thing.get("name"))
3045
docco_ids[name] = {
3046
"name": name,
3047
"labels": [],
3048
}
3049
if getattr(thing.fields, 'field', None) is None:
3050
if name in whitelist:
3051
continue
3052
raise NotAchievedException("no doc fields for %s" % name)
3053
for field in thing.fields.field:
3054
# print("field: (%s)" % str(field))
3055
fieldname = field.get("name")
3056
# print("Got (%s.%s)" % (name,str(fieldname)))
3057
docco_ids[name]["labels"].append(fieldname)
3058
3059
code_ids = self.all_log_format_ids()
3060
# self.progress("Code ids: (%s)" % str(sorted(code_ids.keys())))
3061
# self.progress("Docco ids: (%s)" % str(sorted(docco_ids.keys())))
3062
3063
undocumented = set()
3064
overdocumented = set()
3065
for name in sorted(code_ids.keys()):
3066
if name not in docco_ids:
3067
if name not in whitelist:
3068
undocumented.add(name)
3069
continue
3070
if name in whitelist:
3071
overdocumented.add(name)
3072
seen_labels = {}
3073
for label in code_ids[name]["labels"].split(","):
3074
if label in seen_labels:
3075
raise NotAchievedException("%s.%s is duplicate label" %
3076
(name, label))
3077
seen_labels[label] = True
3078
if label not in docco_ids[name]["labels"]:
3079
msg = ("%s.%s not in documented fields (have (%s))" %
3080
(name, label, ",".join(docco_ids[name]["labels"])))
3081
if name in whitelist:
3082
self.progress(msg)
3083
# a lot of our Replay messages have names but
3084
# nothing more
3085
try:
3086
overdocumented.remove(name)
3087
except KeyError:
3088
pass
3089
continue
3090
raise NotAchievedException(msg)
3091
3092
if len(undocumented):
3093
for name in sorted(undocumented):
3094
self.progress(f"Undocumented message: {name}")
3095
raise NotAchievedException("Undocumented messages found")
3096
if len(overdocumented):
3097
for name in sorted(overdocumented):
3098
self.progress(f"Message documented when it shouldn't be: {name}")
3099
raise NotAchievedException("Overdocumented messages found")
3100
3101
missing = []
3102
for name in sorted(docco_ids):
3103
if name not in code_ids and name not in whitelist:
3104
missing.append(name)
3105
continue
3106
for label in docco_ids[name]["labels"]:
3107
if label not in code_ids[name]["labels"].split(","):
3108
# "name" was found in the XML, so was found in an
3109
# @LoggerMessage markup line, but was *NOT* found
3110
# in our bodgy parsing of the C++ code (in a
3111
# Log_Write call or in the static structures)
3112
raise NotAchievedException("documented field %s.%s not found in code" %
3113
(name, label))
3114
if len(missing) > 0:
3115
raise NotAchievedException("Documented messages (%s) not in code" % missing)
3116
3117
def initialise_after_reboot_sitl(self):
3118
3119
# after reboot stream-rates may be zero. Request streams.
3120
self.drain_mav()
3121
self.wait_heartbeat()
3122
self.set_streamrate(self.sitl_streamrate())
3123
self.progress("Reboot complete")
3124
3125
def customise_SITL_commandline(self,
3126
customisations,
3127
model=None,
3128
defaults_filepath=None,
3129
wipe=False,
3130
set_streamrate_callback=None,
3131
binary=None):
3132
'''customisations could be "--serial5=sim:nmea" '''
3133
self.contexts[-1].sitl_commandline_customised = True
3134
self.mav.close()
3135
self.stop_SITL()
3136
self.start_SITL(binary=binary,
3137
model=model,
3138
defaults_filepath=defaults_filepath,
3139
customisations=customisations,
3140
wipe=wipe)
3141
self.mav.do_connect()
3142
tstart = time.time()
3143
while True:
3144
if time.time() - tstart > 30:
3145
raise NotAchievedException("Failed to customise")
3146
try:
3147
m = self.wait_heartbeat(drain_mav=True)
3148
if m.type == 0:
3149
self.progress("Bad heartbeat: %s" % str(m))
3150
continue
3151
except IOError:
3152
pass
3153
break
3154
if set_streamrate_callback is not None:
3155
set_streamrate_callback()
3156
else:
3157
self.set_streamrate(self.sitl_streamrate())
3158
3159
self.assert_receive_message('RC_CHANNELS', timeout=15)
3160
3161
# stash our arguments in case we need to preserve them in
3162
# reboot_sitl with Valgrind active:
3163
if self.valgrind or self.callgrind:
3164
self.valgrind_restart_model = model
3165
self.valgrind_restart_defaults_filepath = defaults_filepath
3166
self.valgrind_restart_customisations = customisations
3167
3168
def default_parameter_list(self):
3169
ret = {
3170
'LOG_DISARMED': 1,
3171
# also lower logging rate to reduce log sizes
3172
'LOG_DARM_RATEMAX': 5,
3173
'LOG_FILE_RATEMAX': 10,
3174
}
3175
if self.force_ahrs_type is not None:
3176
if self.force_ahrs_type == 2:
3177
ret["EK2_ENABLE"] = 1
3178
if self.force_ahrs_type == 3:
3179
ret["EK3_ENABLE"] = 1
3180
ret["AHRS_EKF_TYPE"] = self.force_ahrs_type
3181
if self.num_aux_imus > 0:
3182
ret["SIM_IMU_COUNT"] = self.num_aux_imus + 3
3183
if self.replay:
3184
ret["LOG_REPLAY"] = 1
3185
return ret
3186
3187
def apply_default_parameter_list(self):
3188
self.set_parameters(self.default_parameter_list())
3189
3190
def apply_default_parameters(self):
3191
self.apply_defaultfile_parameters()
3192
self.apply_default_parameter_list()
3193
self.reboot_sitl()
3194
3195
def reset_SITL_commandline(self):
3196
self.progress("Resetting SITL commandline to default")
3197
self.stop_SITL()
3198
try:
3199
del self.valgrind_restart_customisations
3200
except Exception:
3201
pass
3202
self.start_SITL(wipe=True)
3203
self.set_streamrate(self.sitl_streamrate())
3204
self.apply_default_parameters()
3205
self.progress("Reset SITL commandline to default")
3206
3207
def pause_SITL(self):
3208
'''temporarily stop the SITL process from running. Note that
3209
simulation time will not move forward!'''
3210
# self.progress("Pausing SITL")
3211
if sys.platform == 'cygwin':
3212
# Maintain original behaviour under cygwin as SIGTSTP has not been tested
3213
self.sitl.kill(signal.SIGSTOP)
3214
3215
else:
3216
# SIGTSTP can be ignored by GDB allowing easier debugging rather than having GDB break at every pause
3217
# EG add:
3218
# handle SIGTSTP nostop noprint pass
3219
# handle SIGCONT nostop noprint pass
3220
self.sitl.kill(signal.SIGTSTP)
3221
3222
def unpause_SITL(self):
3223
# self.progress("Unpausing SITL")
3224
self.sitl.kill(signal.SIGCONT)
3225
3226
def stop_SITL(self):
3227
self.progress("Stopping SITL")
3228
self.expect_list_remove(self.sitl)
3229
util.pexpect_close(self.sitl)
3230
self.sitl = None
3231
3232
def start_test(self, description):
3233
self.progress("##################################################################################")
3234
self.progress("########## %s ##########" % description)
3235
self.progress("##################################################################################")
3236
3237
def try_symlink_tlog(self):
3238
self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")
3239
self.progress("buildlog=%s" % self.buildlog)
3240
if os.path.exists(self.buildlog):
3241
os.unlink(self.buildlog)
3242
try:
3243
os.link(self.logfile, self.buildlog)
3244
except OSError as error:
3245
self.progress("OSError [%d]: %s" % (error.errno, error.strerror))
3246
self.progress("Problem: Failed to create link: %s => %s, "
3247
"will copy tlog manually to target location" %
3248
(self.logfile, self.buildlog))
3249
self.copy_tlog = True
3250
3251
#################################################
3252
# GENERAL UTILITIES
3253
#################################################
3254
def expect_list_clear(self):
3255
"""clear the expect list."""
3256
for p in self.expect_list[:]:
3257
self.expect_list.remove(p)
3258
3259
def expect_list_extend(self, list_to_add):
3260
"""Extend the expect list."""
3261
self.expect_list.extend(list_to_add)
3262
3263
def expect_list_add(self, item):
3264
"""Extend the expect list."""
3265
self.expect_list.extend([item])
3266
3267
def expect_list_remove(self, item):
3268
"""Remove item from the expect list."""
3269
self.expect_list.remove(item)
3270
3271
def heartbeat_interval_ms(self):
3272
c = self.context_get()
3273
if c is None:
3274
return 1000
3275
return c.heartbeat_interval_ms
3276
3277
def set_heartbeat_interval_ms(self, interval_ms):
3278
c = self.context_get()
3279
if c is None:
3280
raise ValueError("No context")
3281
if c.original_heartbeat_interval_ms is None:
3282
c.original_heartbeat_interval_ms = c.heartbeat_interval_ms
3283
c.heartbeat_interval_ms = interval_ms
3284
3285
def set_heartbeat_rate(self, rate_hz):
3286
if rate_hz == 0:
3287
self.set_heartbeat_interval_ms(None)
3288
return
3289
self.set_heartbeat_interval_ms(1000.0/rate_hz)
3290
3291
def do_heartbeats(self, force=False):
3292
# self.progress("do_heartbeats")
3293
if self.heartbeat_interval_ms() is None and not force:
3294
return
3295
x = self.mav.messages.get("SYSTEM_TIME", None)
3296
now_wc = time.time()
3297
if (force or
3298
x is None or
3299
self.last_heartbeat_time_ms is None or
3300
self.last_heartbeat_time_ms < x.time_boot_ms or
3301
x.time_boot_ms - self.last_heartbeat_time_ms > self.heartbeat_interval_ms() or
3302
now_wc - self.last_heartbeat_time_wc_s > 1):
3303
if x is not None:
3304
self.last_heartbeat_time_ms = x.time_boot_ms
3305
self.last_heartbeat_time_wc_s = now_wc
3306
self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,
3307
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
3308
0,
3309
0,
3310
0)
3311
3312
def drain_all_pexpects(self):
3313
for p in self.expect_list:
3314
util.pexpect_drain(p)
3315
3316
def idle_hook(self, mav):
3317
"""Called when waiting for a mavlink message."""
3318
if self.in_drain_mav:
3319
return
3320
self.drain_all_pexpects()
3321
3322
class MessageHook():
3323
'''base class for objects that watch the message stream and check for
3324
validity of fields'''
3325
def __init__(self, suite):
3326
self.suite = suite
3327
3328
def process(self):
3329
pass
3330
3331
def progress_prefix(self):
3332
return ""
3333
3334
def progress(self, string):
3335
string = self.progress_prefix() + string
3336
self.suite.progress(string)
3337
3338
def hook_removed(self):
3339
pass
3340
3341
class FailFastStatusText(MessageHook):
3342
'''watches STATUSTEXT message; any message matching passed-in
3343
patterns causes a NotAchievedException to be thrown'''
3344
def __init__(self, suite, texts, regex: bool = False):
3345
super(TestSuite.FailFastStatusText, self).__init__(suite)
3346
if isinstance(texts, str):
3347
texts = [texts]
3348
self.texts = texts
3349
self.regex = regex
3350
3351
def progress_prefix(self):
3352
return "FFST: "
3353
3354
def process(self, mav, m):
3355
if m.get_type() != 'STATUSTEXT':
3356
return
3357
3358
for text in self.texts:
3359
if self.regex:
3360
found = re.match(text, m.text)
3361
else:
3362
found = text.lower() in m.text.lower()
3363
if found:
3364
raise NotAchievedException(f"Fail-fast text found: {m.text}")
3365
3366
class ValidateIntPositionAgainstSimState(MessageHook):
3367
'''monitors a message containing a position containing lat/lng in 1e7,
3368
makes sure it stays close to SIMSTATE'''
3369
def __init__(self, suite, other_int_message_name, max_allowed_divergence=150):
3370
super(TestSuite.ValidateIntPositionAgainstSimState, self).__init__(suite)
3371
self.other_int_message_name = other_int_message_name
3372
self.max_allowed_divergence = max_allowed_divergence
3373
self.max_divergence = 0
3374
self.gpi = None
3375
self.simstate = None
3376
self.last_print = 0
3377
self.min_print_interval = 1 # seconds
3378
3379
def progress_prefix(self):
3380
return "VIPASS: "
3381
3382
def process(self, mav, m):
3383
if m.get_type() == self.other_int_message_name:
3384
self.gpi = m
3385
elif m.get_type() == 'SIMSTATE':
3386
self.simstate = m
3387
if self.gpi is None:
3388
return
3389
if self.simstate is None:
3390
return
3391
3392
divergence = self.suite.get_distance_int(self.gpi, self.simstate)
3393
if (time.time() - self.last_print > self.min_print_interval or
3394
divergence > self.max_divergence):
3395
self.progress(f"distance(SIMSTATE,{self.other_int_message_name})={divergence:.5f}m")
3396
self.last_print = time.time()
3397
if divergence > self.max_divergence:
3398
self.max_divergence = divergence
3399
if divergence > self.max_allowed_divergence:
3400
raise NotAchievedException(
3401
"%s diverged from simstate by %fm (max=%fm" %
3402
(self.other_int_message_name, divergence, self.max_allowed_divergence,))
3403
3404
def hook_removed(self):
3405
self.progress(f"Maximum divergence was {self.max_divergence}m (max={self.max_allowed_divergence}m)")
3406
3407
class ValidateGlobalPositionIntAgainstSimState(ValidateIntPositionAgainstSimState):
3408
def __init__(self, suite, **kwargs):
3409
super(TestSuite.ValidateGlobalPositionIntAgainstSimState, self).__init__(suite, 'GLOBAL_POSITION_INT', **kwargs)
3410
3411
class ValidateAHRS3AgainstSimState(ValidateIntPositionAgainstSimState):
3412
def __init__(self, suite, **kwargs):
3413
super(TestSuite.ValidateAHRS3AgainstSimState, self).__init__(suite, 'AHRS3', **kwargs)
3414
3415
def message_hook(self, mav, msg):
3416
"""Called as each mavlink msg is received."""
3417
# print("msg: %s" % str(msg))
3418
if msg.get_type() == 'STATUSTEXT':
3419
self.progress("AP: %s" % msg.text, send_statustext=False)
3420
3421
self.write_msg_to_tlog(msg)
3422
3423
self.idle_hook(mav)
3424
self.do_heartbeats()
3425
3426
for h in self.message_hooks:
3427
if isinstance(h, TestSuite.MessageHook):
3428
h.process(mav, msg)
3429
continue
3430
# assume it's a function
3431
h(mav, msg)
3432
3433
def send_message_hook(self, msg, x):
3434
self.write_msg_to_tlog(msg)
3435
3436
def write_msg_to_tlog(self, msg):
3437
usec = int(time.time() * 1.0e6)
3438
if self.tlog is None:
3439
tlog_filename = "autotest-%u.tlog" % usec
3440
self.tlog = open(tlog_filename, 'wb')
3441
3442
content = bytearray(struct.pack('>Q', usec) + msg.get_msgbuf())
3443
self.tlog.write(content)
3444
3445
def expect_callback(self, e):
3446
"""Called when waiting for a expect pattern."""
3447
for p in self.expect_list:
3448
if p == e:
3449
continue
3450
util.pexpect_drain(p)
3451
self.drain_mav(quiet=True)
3452
self.do_heartbeats()
3453
3454
def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False):
3455
'''drain all data on mavlink connection mav (defaulting to self.mav).
3456
It is assumed that this connection is connected to the normal
3457
simulation.'''
3458
if mav is None:
3459
mav = self.mav
3460
count = 0
3461
tstart = time.time()
3462
self.pause_SITL()
3463
# sometimes we recv() when the process is likely to go away..
3464
old_autoreconnect = mav.autoreconnect
3465
mav.autoreconnect = False
3466
while True:
3467
try:
3468
this = mav.recv(1000000)
3469
except Exception:
3470
mav.autoreconnect = old_autoreconnect
3471
self.unpause_SITL()
3472
raise
3473
if len(this) == 0:
3474
break
3475
count += len(this)
3476
mav.autoreconnect = old_autoreconnect
3477
self.unpause_SITL()
3478
if quiet:
3479
return
3480
tdelta = time.time() - tstart
3481
if tdelta == 0:
3482
rate = "instantly"
3483
else:
3484
rate = "%f/s" % (count/float(tdelta),)
3485
self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate), send_statustext=False)
3486
if freshen_sim_time:
3487
self.get_sim_time()
3488
3489
def drain_mav(self, mav=None, unparsed=False, quiet=True):
3490
'''parse all data available on connection mav (defaulting to
3491
self.mav). It is assumed that mav is connected to the normal
3492
simulation'''
3493
if unparsed:
3494
return self.drain_mav_unparsed(quiet=quiet, mav=mav)
3495
if mav is None:
3496
mav = self.mav
3497
self.in_drain_mav = True
3498
count = 0
3499
tstart = time.time()
3500
timeout = 120
3501
failed_to_drain = False
3502
self.pause_SITL()
3503
# sometimes we recv() when the process is likely to go away..
3504
old_autoreconnect = mav.autoreconnect
3505
mav.autoreconnect = False
3506
while True:
3507
try:
3508
receive_result = mav.recv_msg()
3509
except Exception:
3510
mav.autoreconnect = True
3511
self.unpause_SITL()
3512
raise
3513
if receive_result is None:
3514
break
3515
count += 1
3516
if time.time() - tstart > timeout:
3517
# ArduPilot can produce messages faster than we can
3518
# consume them. Until a better solution is found,
3519
# just die if that seems to be the case:
3520
failed_to_drain = True
3521
quiet = False
3522
mav.autoreconnect = old_autoreconnect
3523
self.unpause_SITL()
3524
if quiet:
3525
self.in_drain_mav = False
3526
return
3527
tdelta = time.time() - tstart
3528
if tdelta == 0:
3529
rate = "instantly"
3530
else:
3531
rate = "%f/s" % (count/float(tdelta),)
3532
3533
if not quiet:
3534
self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False)
3535
3536
if failed_to_drain:
3537
raise NotAchievedException("Did not fully drain MAV within %ss" % timeout)
3538
3539
self.in_drain_mav = False
3540
3541
def do_timesync_roundtrip(self, quiet=False, timeout_in_wallclock=False):
3542
if not quiet:
3543
self.progress("Doing timesync roundtrip")
3544
if timeout_in_wallclock:
3545
tstart = time.time()
3546
else:
3547
tstart = self.get_sim_time()
3548
self.mav.mav.timesync_send(0, self.timesync_number * 1000 + self.mav.source_system)
3549
while True:
3550
if timeout_in_wallclock:
3551
now = time.time()
3552
else:
3553
now = self.get_sim_time_cached()
3554
if now - tstart > 5:
3555
raise AutoTestTimeoutException("Did not get timesync response")
3556
m = self.mav.recv_match(type='TIMESYNC', blocking=True, timeout=1)
3557
if not quiet:
3558
self.progress("Received: %s" % str(m))
3559
if m is None:
3560
continue
3561
if m.ts1 % 1000 != self.mav.source_system:
3562
self.progress("this isn't a response to our timesync (%s)" % (m.ts1 % 1000))
3563
continue
3564
if m.tc1 == 0:
3565
# this should also not happen:
3566
self.progress("this is a timesync request, which we don't answer")
3567
continue
3568
if int(m.ts1 / 1000) != self.timesync_number:
3569
self.progress("this isn't the one we just sent")
3570
continue
3571
if m.get_srcSystem() != self.mav.target_system:
3572
self.progress("response from system other than our target (want=%u got=%u" %
3573
(self.mav.target_system, m.get_srcSystem()))
3574
continue
3575
# no component check ATM because we send broadcast...
3576
# if m.get_srcComponent() != self.mav.target_component:
3577
# self.progress("response from component other than our target (got=%u want=%u)" % (m.get_srcComponent(), self.mav.target_component)) # noqa
3578
# continue
3579
if not quiet:
3580
self.progress("Received TIMESYNC response after %fs" % (now - tstart))
3581
self.timesync_number += 1
3582
break
3583
3584
def log_filepath(self, lognum):
3585
'''return filepath to lognum (where lognum comes from LOG_ENTRY'''
3586
log_list = self.log_list()
3587
return log_list[lognum-1]
3588
3589
def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):
3590
tocheck = len(bytes1)
3591
if maxlen is not None:
3592
if tocheck > maxlen:
3593
tocheck = maxlen
3594
for i in range(0, tocheck):
3595
if bytes1[i] != bytes2[i]:
3596
raise NotAchievedException("differ at offset %u" % i)
3597
3598
def assert_home_position_not_set(self):
3599
try:
3600
self.poll_home_position()
3601
except NotAchievedException:
3602
return
3603
3604
# if home.lng != 0: etc
3605
3606
raise NotAchievedException("Home is set when it shouldn't be")
3607
3608
def HIGH_LATENCY2(self):
3609
'''test sending of HIGH_LATENCY2'''
3610
3611
# set airspeed sensor type to DLVR for air temperature message testing
3612
if not self.is_plane():
3613
# Plane does not have enable parameter
3614
self.set_parameter("ARSPD_ENABLE", 1)
3615
self.set_parameter("ARSPD_BUS", 2)
3616
self.set_parameter("ARSPD_TYPE", 7)
3617
self.reboot_sitl()
3618
3619
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True, verbose=True, timeout=30)
3620
3621
# should not be getting HIGH_LATENCY2 by default
3622
m = self.assert_not_receive_message('HIGH_LATENCY2', timeout=2)
3623
m = self.poll_message("HIGH_LATENCY2")
3624
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:
3625
raise NotAchievedException("Expected GPS to be OK")
3626
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)
3627
self.set_parameter("SIM_GPS1_TYPE", 0)
3628
self.delay_sim_time(10)
3629
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)
3630
m = self.poll_message("HIGH_LATENCY2")
3631
self.progress(self.dump_message_verbose(m))
3632
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) == 0:
3633
raise NotAchievedException("Expected GPS to be failed")
3634
3635
self.start_subtest("HIGH_LATENCY2 location")
3636
self.set_parameter("SIM_GPS1_TYPE", 1)
3637
self.delay_sim_time(10)
3638
m = self.poll_message("HIGH_LATENCY2")
3639
self.progress(self.dump_message_verbose(m))
3640
loc = mavutil.location(m.latitude, m.longitude, m.altitude, 0)
3641
dist = self.get_distance_int(loc, self.sim_location_int())
3642
3643
if dist > 1:
3644
raise NotAchievedException("Bad location from HIGH_LATENCY2")
3645
3646
self.start_subtest("HIGH_LATENCY2 Air Temperature")
3647
m = self.poll_message("HIGH_LATENCY2")
3648
mavutil.dump_message_verbose(sys.stdout, m)
3649
3650
if m.temperature_air == -128: # High_Latency2 defaults to INT8_MIN for no temperature available
3651
raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2")
3652
self.HIGH_LATENCY2_links()
3653
3654
def context_set_send_debug_trap_on_exceptions(self, value=True):
3655
'''send a debug trap to ArduPilot if an ErrorException is raised.'''
3656
3657
# this is a diagnostic tool, only expected to be used for
3658
# debugging, never for committed code
3659
3660
def trace_calls(frame, event, arg):
3661
if event == 'exception':
3662
exc_type, exc_value, tb = arg
3663
if issubclass(exc_type, ErrorException):
3664
print(f"[Tracer] Exception raised: {exc_type}")
3665
self.send_debug_trap()
3666
return trace_calls
3667
3668
context = self.context_get()
3669
3670
if value:
3671
if sys.gettrace() is not None:
3672
raise ValueError("Can't trace, something else already is")
3673
sys.settrace(trace_calls)
3674
context.raising_debug_trap_on_exceptions = True
3675
return
3676
3677
if not sys.gettrace():
3678
raise ValueError("Expected to see something tracing")
3679
3680
context.raising_debug_trap_on_exceptions = False
3681
sys.settrace(None)
3682
3683
def context_set_message_rate_hz(self, id, rate_hz, run_cmd=None):
3684
if run_cmd is None:
3685
run_cmd = self.run_cmd
3686
3687
overridden_message_rates = self.context_get().overridden_message_rates
3688
3689
if id not in overridden_message_rates:
3690
overridden_message_rates[id] = self.measure_message_rate(id)
3691
3692
self.set_message_rate_hz(id, rate_hz, run_cmd=run_cmd)
3693
3694
def HIGH_LATENCY2_links(self):
3695
3696
self.start_subtest("SerialProtocol_MAVLinkHL links")
3697
3698
ex = None
3699
self.context_push()
3700
mav2 = None
3701
try:
3702
3703
self.set_parameter("SERIAL2_PROTOCOL", 43) # HL)
3704
3705
self.reboot_sitl()
3706
3707
mav2 = mavutil.mavlink_connection(
3708
"tcp:localhost:%u" % self.adjust_ardupilot_port(5763),
3709
robust_parsing=True,
3710
source_system=7,
3711
source_component=7,
3712
)
3713
3714
self.start_subsubtest("Don't get HIGH_LATENCY2 by default")
3715
for mav in self.mav, mav2:
3716
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav, timeout=10)
3717
3718
self.start_subsubtest("Get HIGH_LATENCY2 upon link enabled only on HL link")
3719
for run_cmd in self.run_cmd, self.run_cmd_int:
3720
self.run_cmd_enable_high_latency(True, run_cmd=run_cmd)
3721
self.assert_receive_message("HIGH_LATENCY2", mav=mav2, timeout=10)
3722
self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)
3723
3724
self.start_subsubtest("Not get HIGH_LATENCY2 upon HL disable")
3725
self.run_cmd_enable_high_latency(False, run_cmd=run_cmd)
3726
self.delay_sim_time(10)
3727
self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)
3728
self.drain_mav(mav2)
3729
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)
3730
3731
self.start_subsubtest("Stream rate adjustments")
3732
self.run_cmd_enable_high_latency(True)
3733
self.assert_message_rate_hz("HIGH_LATENCY2", 0.2, ndigits=1, mav=mav2, sample_period=60)
3734
for test_rate in (1, 0.1, 2):
3735
self.test_rate(
3736
"HIGH_LATENCY2 on enabled link",
3737
test_rate,
3738
test_rate,
3739
mav=mav2,
3740
ndigits=1,
3741
victim_message="HIGH_LATENCY2",
3742
message_rate_sample_period=60,
3743
)
3744
self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)
3745
self.run_cmd_enable_high_latency(False)
3746
3747
self.start_subsubtest("Not get HIGH_LATENCY2 after disabling after playing with rates")
3748
self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)
3749
self.delay_sim_time(1)
3750
self.drain_mav(mav2)
3751
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)
3752
3753
self.start_subsubtest("Enable and disable should not affect non-HL links getting HIGH_LATENCY2")
3754
self.set_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3755
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3756
3757
self.run_cmd_enable_high_latency(True)
3758
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav),
3759
3760
self.run_cmd_enable_high_latency(False)
3761
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3762
except Exception as e:
3763
self.print_exception_caught(e)
3764
ex = e
3765
3766
self.context_pop()
3767
3768
self.reboot_sitl()
3769
3770
self.set_message_rate_hz("HIGH_LATENCY2", 0)
3771
3772
if ex is not None:
3773
raise ex
3774
3775
def download_full_log_list(self, print_logs=True):
3776
tstart = self.get_sim_time()
3777
self.mav.mav.log_request_list_send(self.sysid_thismav(),
3778
1, # target component
3779
0,
3780
0xffff)
3781
logs = {}
3782
last_id = None
3783
num_logs = None
3784
while True:
3785
now = self.get_sim_time_cached()
3786
if now - tstart > 5:
3787
raise NotAchievedException("Did not download list")
3788
m = self.mav.recv_match(type='LOG_ENTRY',
3789
blocking=True,
3790
timeout=1)
3791
if print_logs:
3792
self.progress("Received (%s)" % str(m))
3793
if m is None:
3794
continue
3795
logs[m.id] = m
3796
if last_id is None:
3797
if m.num_logs == 0:
3798
# caller to guarantee this works:
3799
raise NotAchievedException("num_logs is zero")
3800
num_logs = m.num_logs
3801
else:
3802
if m.id != last_id + 1:
3803
raise NotAchievedException("Sequence not increasing")
3804
if m.num_logs != num_logs:
3805
raise NotAchievedException("Number of logs changed")
3806
if m.time_utc < 1000 and m.id != m.num_logs:
3807
raise NotAchievedException("Bad timestamp")
3808
if m.id != m.last_log_num:
3809
if m.size == 0:
3810
raise NotAchievedException("Zero-sized log")
3811
last_id = m.id
3812
if m.id == m.last_log_num:
3813
self.progress("Got all logs")
3814
break
3815
3816
# ensure we don't get any extras:
3817
self.assert_not_receiving_message('LOG_ENTRY', timeout=2)
3818
3819
return logs
3820
3821
def TestLogDownloadWrap(self):
3822
"""Test log wrapping."""
3823
if self.is_tracker():
3824
# tracker starts armed, which is annoying
3825
return
3826
self.progress("Ensuring we have contents we care about")
3827
self.set_parameter("LOG_FILE_DSRMROT", 1)
3828
self.set_parameter("LOG_DISARMED", 0)
3829
self.reboot_sitl()
3830
logspath = Path("logs")
3831
3832
def create_num_logs(num_logs, logsdir, clear_logsdir=True):
3833
if clear_logsdir:
3834
shutil.rmtree(logsdir, ignore_errors=True)
3835
logsdir.mkdir()
3836
lastlogfile_path = logsdir / Path("LASTLOG.TXT")
3837
self.progress(f"Add LASTLOG.TXT file with counter at {num_logs}")
3838
with open(lastlogfile_path, 'w') as lastlogfile:
3839
lastlogfile.write(f"{num_logs}\n")
3840
self.progress(f"Create fakelogs from 1 to {num_logs} on logs directory")
3841
for ii in range(1, num_logs + 1):
3842
new_log = logsdir / Path(f"{str(ii).zfill(8)}.BIN")
3843
with open(new_log, 'w+') as logfile:
3844
logfile.write(f"I AM LOG {ii}\n")
3845
logfile.write('1' * ii)
3846
3847
def verify_logs(test_log_num):
3848
try:
3849
wrap = False
3850
offset = 0
3851
max_logs_num = int(self.get_parameter("LOG_MAX_FILES"))
3852
if test_log_num > max_logs_num:
3853
wrap = True
3854
offset = test_log_num - max_logs_num
3855
test_log_num = max_logs_num
3856
logs_dict = self.download_full_log_list(print_logs=False)
3857
if len(logs_dict) != test_log_num:
3858
raise NotAchievedException(
3859
f"Didn't get the full log list, expect {test_log_num} got {len(logs_dict)}")
3860
self.progress("Checking logs size are matching")
3861
start_log = offset if wrap else 1
3862
for ii in range(start_log, test_log_num + 1 - offset):
3863
log_i = logspath / Path(f"{str(ii + offset).zfill(8)}.BIN")
3864
if logs_dict[ii].size != log_i.stat().st_size:
3865
logs_dict = self.download_full_log_list(print_logs=False)
3866
# sometimes we don't have finish writing the log, so get it again prevent failure
3867
if logs_dict[ii].size != log_i.stat().st_size:
3868
raise NotAchievedException(
3869
f"Log{ii} size mismatch : {logs_dict[ii].size} vs {log_i.stat().st_size}"
3870
)
3871
if wrap:
3872
self.progress("Checking wrapped logs size are matching")
3873
for ii in range(1, offset):
3874
log_i = logspath / Path(f"{str(ii).zfill(8)}.BIN")
3875
if logs_dict[test_log_num + 1 - offset + ii].size != log_i.stat().st_size:
3876
self.progress(f"{logs_dict[test_log_num + 1 - offset + ii]}")
3877
raise NotAchievedException(
3878
f"Log{test_log_num + 1 - offset + ii} size mismatch :"
3879
f" {logs_dict[test_log_num + 1 - offset + ii].size} vs {log_i.stat().st_size}"
3880
)
3881
except NotAchievedException as e:
3882
shutil.rmtree(logspath, ignore_errors=True)
3883
logspath.mkdir()
3884
with open(logspath / Path("LASTLOG.TXT"), 'w') as lastlogfile:
3885
lastlogfile.write("1\n")
3886
raise e
3887
3888
def add_and_verify_log(test_log_num):
3889
self.wait_ready_to_arm()
3890
self.arm_vehicle()
3891
self.delay_sim_time(1)
3892
self.disarm_vehicle()
3893
self.delay_sim_time(10)
3894
verify_logs(test_log_num + 1)
3895
3896
def create_and_verify_logs(test_log_num, clear_logsdir=True):
3897
self.progress(f"Test {test_log_num} logs")
3898
create_num_logs(test_log_num, logspath, clear_logsdir)
3899
self.reboot_sitl()
3900
verify_logs(test_log_num)
3901
self.start_subsubtest("Adding one more log")
3902
add_and_verify_log(test_log_num)
3903
3904
self.start_subtest("Checking log list match with filesystem info")
3905
create_and_verify_logs(500)
3906
create_and_verify_logs(10)
3907
create_and_verify_logs(1)
3908
3909
self.start_subtest("Change LOG_MAX_FILES and Checking log list match with filesystem info")
3910
self.set_parameter("LOG_MAX_FILES", 250)
3911
create_and_verify_logs(250)
3912
self.set_parameter("LOG_MAX_FILES", 1)
3913
create_and_verify_logs(1)
3914
3915
self.start_subtest("Change LOG_MAX_FILES, don't clear old logs and Checking log list match with filesystem info")
3916
self.set_parameter("LOG_MAX_FILES", 500)
3917
create_and_verify_logs(500)
3918
self.set_parameter("LOG_MAX_FILES", 250)
3919
create_and_verify_logs(250, clear_logsdir=False)
3920
3921
# cleanup
3922
shutil.rmtree(logspath, ignore_errors=True)
3923
3924
def TestLogDownload(self):
3925
"""Test Onboard Log Download."""
3926
if self.is_tracker():
3927
# tracker starts armed, which is annoying
3928
return
3929
self.progress("Ensuring we have contents we care about")
3930
self.set_parameter("LOG_FILE_DSRMROT", 1)
3931
self.set_parameter("LOG_DISARMED", 0)
3932
self.reboot_sitl()
3933
original_log_list = self.log_list()
3934
for i in range(0, 10):
3935
self.wait_ready_to_arm()
3936
self.arm_vehicle()
3937
self.delay_sim_time(1)
3938
self.disarm_vehicle()
3939
new_log_list = self.log_list()
3940
new_log_count = len(new_log_list) - len(original_log_list)
3941
if new_log_count != 10:
3942
raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" %
3943
(new_log_count, original_log_list, new_log_list))
3944
self.progress("Directory contents: %s" % str(new_log_list))
3945
3946
self.download_full_log_list()
3947
log_id = 5
3948
ofs = 6
3949
count = 2
3950
self.start_subtest("downloading %u bytes from offset %u from log_id %u" %
3951
(count, ofs, log_id))
3952
self.mav.mav.log_request_data_send(self.sysid_thismav(),
3953
1, # target component
3954
log_id,
3955
ofs,
3956
count)
3957
m = self.assert_receive_message('LOG_DATA', timeout=2)
3958
if m.ofs != ofs:
3959
raise NotAchievedException("Incorrect offset")
3960
if m.count != count:
3961
raise NotAchievedException("Did not get correct number of bytes")
3962
log_filepath = self.log_filepath(log_id)
3963
self.progress("Checking against log_filepath (%s)" % str(log_filepath))
3964
with open(log_filepath, "rb") as bob:
3965
bob.seek(ofs)
3966
actual_bytes = bob.read(2)
3967
actual_bytes = bytearray(actual_bytes)
3968
if m.data[0] != actual_bytes[0]:
3969
raise NotAchievedException("Bad first byte got=(0x%02x) want=(0x%02x)" %
3970
(m.data[0], actual_bytes[0]))
3971
if m.data[1] != actual_bytes[1]:
3972
raise NotAchievedException("Bad second byte")
3973
3974
log_id = 7
3975
log_filepath = self.log_filepath(log_id)
3976
self.start_subtest("Downloading log id %u (%s)" % (log_id, log_filepath))
3977
with open(log_filepath, "rb") as bob:
3978
actual_bytes = bytearray(bob.read())
3979
3980
# get the size first
3981
self.mav.mav.log_request_list_send(self.sysid_thismav(),
3982
1, # target component
3983
log_id,
3984
log_id)
3985
log_entry = self.assert_receive_message('LOG_ENTRY', timeout=2, verbose=True)
3986
if log_entry.size != len(actual_bytes):
3987
raise NotAchievedException("Incorrect bytecount")
3988
if log_entry.id != log_id:
3989
raise NotAchievedException("Incorrect log id received")
3990
3991
# download the log file in the normal way:
3992
bytes_to_fetch = 100000
3993
self.progress("Sending request for %u bytes at offset 0" % (bytes_to_fetch,))
3994
tstart = self.get_sim_time()
3995
self.mav.mav.log_request_data_send(
3996
self.sysid_thismav(),
3997
1, # target component
3998
log_id,
3999
0,
4000
bytes_to_fetch
4001
)
4002
bytes_to_read = bytes_to_fetch
4003
if log_entry.size < bytes_to_read:
4004
bytes_to_read = log_entry.size
4005
data_downloaded = []
4006
bytes_read = 0
4007
last_print = 0
4008
while True:
4009
if bytes_read >= bytes_to_read:
4010
break
4011
if self.get_sim_time_cached() - tstart > 120:
4012
raise NotAchievedException("Did not download log in good time")
4013
m = self.assert_receive_message('LOG_DATA', timeout=2)
4014
if m.ofs != bytes_read:
4015
raise NotAchievedException("Unexpected offset")
4016
if m.id != log_id:
4017
raise NotAchievedException("Unexpected id")
4018
if m.count == 0:
4019
raise NotAchievedException("Zero bytes read")
4020
data_downloaded.extend(m.data[0:m.count])
4021
bytes_read += m.count
4022
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4023
if time.time() - last_print > 10:
4024
last_print = time.time()
4025
self.progress("Read %u/%u" % (bytes_read, bytes_to_read))
4026
4027
self.progress("actual_bytes_len=%u data_downloaded_len=%u" %
4028
(len(actual_bytes), len(data_downloaded)))
4029
self.assert_bytes_equal(actual_bytes, data_downloaded, maxlen=bytes_to_read)
4030
4031
if False:
4032
bytes_to_read = log_entry.size
4033
bytes_read = 0
4034
data_downloaded = []
4035
while bytes_read < bytes_to_read:
4036
bytes_to_fetch = int(random.random() * 100)
4037
if bytes_to_fetch > 90:
4038
bytes_to_fetch = 90
4039
self.progress("Sending request for %u bytes at offset %u" % (bytes_to_fetch, bytes_read))
4040
self.mav.mav.log_request_data_send(
4041
self.sysid_thismav(),
4042
1, # target component
4043
log_id,
4044
bytes_read,
4045
bytes_to_fetch
4046
)
4047
m = self.assert_receive_message('LOG_DATA', timeout=2)
4048
self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4049
if m.ofs != bytes_read:
4050
raise NotAchievedException("Incorrect offset in reply want=%u got=%u (%s)" % (bytes_read, m.ofs, str(m)))
4051
stuff = m.data[0:m.count]
4052
data_downloaded.extend(stuff)
4053
bytes_read += m.count
4054
if len(data_downloaded) != bytes_read:
4055
raise NotAchievedException("extend fail")
4056
4057
if len(actual_bytes) != len(data_downloaded):
4058
raise NotAchievedException("Incorrect length: disk:%u downloaded: %u" %
4059
(len(actual_bytes), len(data_downloaded)))
4060
self.assert_bytes_equal(actual_bytes, data_downloaded)
4061
4062
self.start_subtest("Download log backwards")
4063
bytes_to_read = bytes_to_fetch
4064
if log_entry.size < bytes_to_read:
4065
bytes_to_read = log_entry.size
4066
bytes_read = 0
4067
backwards_data_downloaded = []
4068
last_print = 0
4069
while bytes_read < bytes_to_read:
4070
bytes_to_fetch = int(random.random() * 99) + 1
4071
if bytes_to_fetch > 90:
4072
bytes_to_fetch = 90
4073
if bytes_to_fetch > bytes_to_read - bytes_read:
4074
bytes_to_fetch = bytes_to_read - bytes_read
4075
ofs = bytes_to_read - bytes_read - bytes_to_fetch
4076
# self.progress("bytes_to_read=%u bytes_read=%u bytes_to_fetch=%u ofs=%d" %
4077
# (bytes_to_read, bytes_read, bytes_to_fetch, ofs))
4078
self.mav.mav.log_request_data_send(
4079
self.sysid_thismav(),
4080
1, # target component
4081
log_id,
4082
ofs,
4083
bytes_to_fetch
4084
)
4085
m = self.assert_receive_message('LOG_DATA', timeout=2)
4086
if m.count == 0:
4087
raise NotAchievedException("xZero bytes read (ofs=%u)" % (ofs,))
4088
if m.count > bytes_to_fetch:
4089
raise NotAchievedException("Read too many bytes?!")
4090
stuff = m.data[0:m.count]
4091
stuff.extend(backwards_data_downloaded)
4092
backwards_data_downloaded = stuff
4093
bytes_read += m.count
4094
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4095
if time.time() - last_print > 10:
4096
last_print = time.time()
4097
self.progress("xRead %u/%u" % (bytes_read, bytes_to_read))
4098
4099
self.assert_bytes_equal(actual_bytes, backwards_data_downloaded, maxlen=bytes_to_read)
4100
# if len(actual_bytes) != len(backwards_data_downloaded):
4101
# raise NotAchievedException("Size delta: actual=%u vs downloaded=%u" %
4102
# (len(actual_bytes), len(backwards_data_downloaded)))
4103
4104
def download_log(self, log_id, timeout=360):
4105
tstart = self.get_sim_time()
4106
data_downloaded = []
4107
bytes_read = 0
4108
last_print = 0
4109
while True:
4110
if self.get_sim_time_cached() - tstart > timeout:
4111
raise NotAchievedException("Did not download log in good time")
4112
self.mav.mav.log_request_data_send(
4113
self.sysid_thismav(),
4114
1, # target component
4115
log_id,
4116
bytes_read,
4117
90
4118
)
4119
m = self.assert_receive_message('LOG_DATA', timeout=2)
4120
if m.ofs != bytes_read:
4121
raise NotAchievedException(f"Unexpected offset {bytes_read=} {self.dump_message_verbose(m)}")
4122
if m.id != log_id:
4123
raise NotAchievedException(f"Unexpected id {log_id=} {self.dump_message_verbose(m)}")
4124
data_downloaded.extend(m.data[0:m.count])
4125
bytes_read += m.count
4126
if m.count < 90: # FIXME: constant
4127
break
4128
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4129
if time.time() - last_print > 10:
4130
last_print = time.time()
4131
self.progress(f"{bytes_read=}")
4132
return data_downloaded
4133
4134
def TestLogDownloadLogRestart(self):
4135
'''test logging restarts after log download'''
4136
# self.delay_sim_time(30)
4137
self.set_parameters({
4138
"LOG_FILE_RATEMAX": 1,
4139
})
4140
self.reboot_sitl()
4141
number = self.current_onboard_log_number()
4142
content = self.download_log(number)
4143
print(f"Content is of length {len(content)}")
4144
# current_log_filepath = self.current_onboard_log_filepath()
4145
self.delay_sim_time(5)
4146
new_number = self.current_onboard_log_number()
4147
if number == new_number:
4148
raise NotAchievedException("Did not start logging again")
4149
new_content = self.download_log(new_number)
4150
if len(new_content) == 0:
4151
raise NotAchievedException(f"Unexpected length {len(new_content)=}")
4152
4153
#################################################
4154
# SIM UTILITIES
4155
#################################################
4156
def get_sim_time(self, timeout=60, drain_mav=True):
4157
"""Get SITL time in seconds."""
4158
if drain_mav:
4159
self.drain_mav()
4160
tstart = time.time()
4161
while True:
4162
self.drain_all_pexpects()
4163
if time.time() - tstart > timeout:
4164
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)
4165
4166
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=0.1)
4167
if m is None:
4168
continue
4169
if m.get_srcSystem() != self.sysid_thismav():
4170
continue
4171
4172
return m.time_boot_ms * 1.0e-3
4173
4174
def get_sim_time_cached(self):
4175
"""Get SITL time in seconds."""
4176
x = self.mav.messages.get("SYSTEM_TIME", None)
4177
if x is None:
4178
raise NotAchievedException("No cached time available (%s)" % (self.mav.sysid,))
4179
ret = x.time_boot_ms * 1.0e-3
4180
if ret != self.last_sim_time_cached:
4181
self.last_sim_time_cached = ret
4182
self.last_sim_time_cached_wallclock = time.time()
4183
else:
4184
timeout = 30
4185
if self.valgrind:
4186
timeout *= 10
4187
if time.time() - self.last_sim_time_cached_wallclock > timeout and not self.gdb:
4188
raise AutoTestTimeoutException("sim_time_cached is not updating!")
4189
return ret
4190
4191
def sim_location(self):
4192
"""Return current simulator location."""
4193
m = self.assert_receive_message('SIMSTATE')
4194
return mavutil.location(m.lat*1.0e-7,
4195
m.lng*1.0e-7,
4196
0,
4197
math.degrees(m.yaw))
4198
4199
def sim_location_int(self):
4200
"""Return current simulator location."""
4201
m = self.assert_receive_message('SIMSTATE')
4202
return mavutil.location(m.lat,
4203
m.lng,
4204
0,
4205
math.degrees(m.yaw))
4206
4207
def save_wp(self, ch=7):
4208
"""Trigger RC Aux to save waypoint."""
4209
self.set_rc(ch, 1000)
4210
self.delay_sim_time(1)
4211
self.set_rc(ch, 2000)
4212
self.delay_sim_time(1)
4213
self.set_rc(ch, 1000)
4214
self.delay_sim_time(1)
4215
4216
def correct_wp_seq_numbers(self, wps):
4217
# renumber the items:
4218
count = 0
4219
for item in wps:
4220
item.seq = count
4221
count += 1
4222
4223
def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1):
4224
return self.create_simple_relloc_mission(
4225
self.home_position_as_mav_location(),
4226
items_in,
4227
target_system=target_system,
4228
target_component=target_component,
4229
)
4230
4231
def create_simple_relloc_mission(self, loc, items_in, target_system=1, target_component=1):
4232
'''takes a list of (type, n, e, alt) items. Creates a mission in
4233
absolute frame using alt as relative-to-home and n and e as
4234
offsets in metres from home'''
4235
4236
# add a dummy waypoint for home
4237
items = [(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0)]
4238
items.extend(items_in)
4239
seq = 0
4240
ret = []
4241
for item in items:
4242
if not isinstance(item, tuple):
4243
# hope this is a mission item...
4244
item.seq = seq
4245
seq += 1
4246
ret.append(item)
4247
continue
4248
opts = {}
4249
try:
4250
(t, n, e, alt, opts) = item
4251
except ValueError:
4252
(t, n, e, alt) = item
4253
lat = 0
4254
lng = 0
4255
if n != 0 or e != 0:
4256
relloc = self.offset_location_ne(loc, n, e)
4257
lat = relloc.lat
4258
lng = relloc.lng
4259
frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT
4260
if not self.ardupilot_stores_frame_for_cmd(t):
4261
frame = mavutil.mavlink.MAV_FRAME_GLOBAL
4262
if opts.get('frame', None) is not None:
4263
frame = opts.get('frame')
4264
p1 = opts.get('p1', 0) # should we pass `None` instead?
4265
ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, p1=p1, x=int(lat*1e7), y=int(lng*1e7), z=alt))
4266
seq += 1
4267
4268
return ret
4269
4270
def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):
4271
mission = self.create_simple_relhome_mission(
4272
items,
4273
target_system=target_system,
4274
target_component=target_component)
4275
self.check_mission_upload_download(mission)
4276
4277
def upload_simple_relloc_mission(self, loc, items, target_system=1, target_component=1):
4278
mission = self.create_simple_relloc_mission(
4279
loc,
4280
items,
4281
target_system=target_system,
4282
target_component=target_component)
4283
self.check_mission_upload_download(mission)
4284
4285
def start_flying_simple_relhome_mission(self, items):
4286
'''uploads items, changes mode to auto, waits ready to arm and arms
4287
vehicle. If the first item it a takeoff you can expect the
4288
vehicle to fly after this method returns. On Copter AUTO_OPTIONS
4289
should be 3.
4290
'''
4291
4292
self.upload_simple_relhome_mission(items)
4293
self.set_current_waypoint(0, check_afterwards=False)
4294
4295
self.change_mode('AUTO')
4296
self.wait_ready_to_arm()
4297
4298
self.arm_vehicle()
4299
# copter gets stuck in auto; if you run a mission to
4300
# completion then the mission state machine ends up in a
4301
# "done" state and you can't restart by just setting an
4302
# earlier waypoint:
4303
self.send_cmd(mavutil.mavlink.MAV_CMD_MISSION_START)
4304
4305
def fly_simple_relhome_mission(self, items):
4306
'''uploads items, changes mode to auto, waits ready to arm and arms
4307
vehicle. Then waits for the vehicle to disarm.
4308
'''
4309
self.start_flying_simple_relhome_mission(items)
4310
self.wait_disarmed()
4311
4312
def get_mission_count(self):
4313
return self.get_parameter("MIS_TOTAL")
4314
4315
def run_auxfunc(self,
4316
function,
4317
level,
4318
run_cmd=None,
4319
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
4320
if run_cmd is None:
4321
run_cmd = self.run_cmd
4322
run_cmd(
4323
mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,
4324
p1=function,
4325
p2=level,
4326
want_result=want_result,
4327
)
4328
4329
def assert_mission_count(self, expected):
4330
count = self.get_mission_count()
4331
if count != expected:
4332
raise NotAchievedException("Unexpected count got=%u want=%u" %
4333
(count, expected))
4334
4335
def clear_wp(self, ch=8):
4336
"""Trigger RC Aux to clear waypoint."""
4337
self.progress("Clearing waypoints")
4338
self.set_rc(ch, 1000)
4339
self.delay_sim_time(0.5)
4340
self.set_rc(ch, 2000)
4341
self.delay_sim_time(0.5)
4342
self.set_rc(ch, 1000)
4343
self.assert_mission_count(0)
4344
4345
def log_list(self):
4346
'''return a list of log files present in POSIX-style logging dir'''
4347
ret = sorted(glob.glob("logs/00*.BIN"))
4348
self.progress("log list: %s" % str(ret))
4349
return ret
4350
4351
def assert_parameter_values(self, parameters, epsilon=None):
4352
names = parameters.keys()
4353
got = self.get_parameters(names)
4354
for name in names:
4355
equal = got[name] == parameters[name]
4356
if epsilon is not None:
4357
delta = abs(got[name] - parameters[name])
4358
equal = delta <= epsilon
4359
if not equal:
4360
raise NotAchievedException("parameter %s want=%f got=%f" %
4361
(name, parameters[name], got[name]))
4362
self.progress("%s has expected value %f" % (name, got[name]))
4363
4364
def assert_parameter_value(self, parameter, required, **kwargs):
4365
self.assert_parameter_values({
4366
parameter: required,
4367
}, **kwargs)
4368
4369
def assert_reach_imu_temperature(self, target, timeout):
4370
'''wait to reach a target temperature'''
4371
tstart = self.get_sim_time()
4372
temp_ok = False
4373
last_print_temp = -100
4374
while self.get_sim_time_cached() - tstart < timeout:
4375
m = self.assert_receive_message('RAW_IMU', timeout=2)
4376
temperature = m.temperature*0.01
4377
if temperature >= target:
4378
self.progress("Reached temperature %.1f" % temperature)
4379
temp_ok = True
4380
break
4381
if temperature - last_print_temp > 1:
4382
self.progress("temperature %.1f" % temperature)
4383
last_print_temp = temperature
4384
4385
if not temp_ok:
4386
raise NotAchievedException("target temperature")
4387
4388
def message_has_field_values_field_values_equal(self, fieldname, value, got, epsilon=None):
4389
if isinstance(value, float):
4390
if math.isnan(value) or math.isnan(got):
4391
return math.isnan(value) and math.isnan(got)
4392
4393
if type(value) is not str and epsilon is not None:
4394
return abs(got - value) <= epsilon
4395
4396
return got == value
4397
4398
def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
4399
for (fieldname, value) in fieldvalues.items():
4400
if "[" in fieldname: # fieldname == "arrayname[index]"
4401
assert fieldname[-1] == "]", fieldname
4402
arrayname, index = fieldname.split("[", 1)
4403
index = int(index[:-1])
4404
got = getattr(m, arrayname)[index]
4405
else:
4406
got = getattr(m, fieldname)
4407
4408
value_string = value
4409
got_string = got
4410
enum_name = m.fieldenums_by_name.get(fieldname, None)
4411
if enum_name is not None:
4412
enum = mavutil.mavlink.enums[enum_name]
4413
if getattr(enum, "bitmask", None):
4414
value_strings = []
4415
value_copy = value
4416
shift_value = 1
4417
while value_copy != 0:
4418
if value_copy & 0x1:
4419
value_strings.append(enum[shift_value].name)
4420
else:
4421
value_strings.append("!" + enum[shift_value].name)
4422
shift_value += 1
4423
value_copy = value_copy >> 1
4424
value_string = f"{value_string} {'|'.join(value_strings)}"
4425
elif enum_name != 'AIRSPEED_SENSOR_FLAGS':
4426
# once the ".bitmask" attribute on enumerations
4427
# becomes uniquitous the check the
4428
# AIRSPEED_SENSOR_FLAGS can be removed.
4429
if value not in enum:
4430
raise ValueError(f"Expected value {value} not in enum {enum}")
4431
if got not in enum:
4432
raise ValueError(f"Received value {got} not in enum {enum}")
4433
value_string = f"{value} ({enum[value].name})"
4434
got_string = f"{got} ({enum[got].name})"
4435
4436
if not self.message_has_field_values_field_values_equal(
4437
fieldname, value, got, epsilon=epsilon
4438
):
4439
# see if this is an enumerated field:
4440
self.progress(self.dump_message_verbose(m))
4441
self.progress("Expected %s.%s to be %s, got %s" %
4442
(m.get_type(), fieldname, value_string, got_string))
4443
return False
4444
if verbose:
4445
self.progress("%s.%s has expected value %s" %
4446
(m.get_type(), fieldname, value_string))
4447
return True
4448
4449
def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
4450
if self.message_has_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon):
4451
return
4452
raise NotAchievedException("Did not get expected field values")
4453
4454
def assert_cached_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None):
4455
'''checks the most-recently received instance of message to ensure it
4456
has the correct field values'''
4457
m = self.get_cached_message(message)
4458
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
4459
return m
4460
4461
def assert_received_message_field_values(self,
4462
message,
4463
fieldvalues,
4464
verbose=True,
4465
very_verbose=False,
4466
epsilon=None,
4467
poll=False,
4468
timeout=None,
4469
check_context=False,
4470
):
4471
if poll:
4472
self.poll_message(message)
4473
m = self.assert_receive_message(
4474
message,
4475
verbose=verbose,
4476
very_verbose=very_verbose,
4477
timeout=timeout,
4478
check_context=check_context
4479
)
4480
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
4481
return m
4482
4483
# FIXME: try to use wait_and_maintain here?
4484
def wait_message_field_values(self,
4485
message,
4486
fieldvalues,
4487
timeout=10,
4488
epsilon=None,
4489
instance=None,
4490
minimum_duration=None,
4491
verbose=False,
4492
very_verbose=False,
4493
):
4494
4495
tstart = self.get_sim_time_cached()
4496
pass_start = None
4497
last_debug = 0
4498
while True:
4499
now = self.get_sim_time_cached()
4500
if now - tstart > timeout:
4501
raise NotAchievedException("Field never reached values")
4502
m = self.assert_receive_message(
4503
message,
4504
instance=instance,
4505
verbose=verbose,
4506
very_verbose=very_verbose,
4507
)
4508
if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose):
4509
if minimum_duration is not None:
4510
if pass_start is None:
4511
pass_start = now
4512
continue
4513
delta = now - pass_start
4514
if now - last_debug >= 1:
4515
last_debug = now
4516
self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)")
4517
if delta < minimum_duration:
4518
continue
4519
else:
4520
self.progress("Reached field values")
4521
return m
4522
pass_start = None
4523
4524
def onboard_logging_not_log_disarmed(self):
4525
self.start_subtest("Test LOG_DISARMED-is-false behaviour")
4526
self.set_parameter("LOG_DISARMED", 0)
4527
self.set_parameter("LOG_FILE_DSRMROT", 0)
4528
self.reboot_sitl()
4529
self.wait_ready_to_arm() # let things setttle
4530
self.start_subtest("Ensure setting LOG_DISARMED yields a new file")
4531
original_list = self.log_list()
4532
self.progress("original list: %s" % str(original_list))
4533
self.set_parameter("LOG_DISARMED", 1)
4534
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4535
new_list = self.log_list()
4536
self.progress("new list: %s" % str(new_list))
4537
if len(new_list) - len(original_list) != 1:
4538
raise NotAchievedException("Got more than one new log")
4539
self.set_parameter("LOG_DISARMED", 0)
4540
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4541
new_list = self.log_list()
4542
if len(new_list) - len(original_list) != 1:
4543
raise NotAchievedException("Got more or less than one new log after toggling LOG_DISARMED off")
4544
4545
self.start_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")
4546
self.set_parameter("LOG_DISARMED", 1)
4547
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4548
new_new_list = self.log_list()
4549
if len(new_new_list) != len(new_list):
4550
raise NotAchievedException("Got extra files when toggling LOG_DISARMED")
4551
self.set_parameter("LOG_DISARMED", 0)
4552
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4553
new_new_list = self.log_list()
4554
if len(new_new_list) != len(new_list):
4555
raise NotAchievedException("Got extra files when toggling LOG_DISARMED to 0 again")
4556
self.end_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")
4557
4558
self.start_subtest("Check disarm rot when log disarmed is zero")
4559
self.assert_parameter_value("LOG_DISARMED", 0)
4560
self.set_parameter("LOG_FILE_DSRMROT", 1)
4561
old_speedup = self.get_parameter("SIM_SPEEDUP")
4562
# reduce speedup to reduce chance of race condition here
4563
self.set_parameter("SIM_SPEEDUP", 1)
4564
pre_armed_list = self.log_list()
4565
if self.is_copter() or self.is_heli():
4566
self.set_parameter("DISARM_DELAY", 0)
4567
self.arm_vehicle()
4568
post_armed_list = self.log_list()
4569
if len(post_armed_list) != len(pre_armed_list):
4570
raise NotAchievedException("Got unexpected new log")
4571
self.disarm_vehicle()
4572
old_speedup = self.set_parameter("SIM_SPEEDUP", old_speedup)
4573
post_disarmed_list = self.log_list()
4574
if len(post_disarmed_list) != len(post_armed_list):
4575
raise NotAchievedException("Log rotated immediately")
4576
self.progress("Allowing time for post-disarm-logging to occur if it will")
4577
self.delay_sim_time(5)
4578
post_disarmed_post_delay_list = self.log_list()
4579
if len(post_disarmed_post_delay_list) != len(post_disarmed_list):
4580
raise NotAchievedException("Got log rotation when we shouldn't have")
4581
self.progress("Checking that arming does produce a new log")
4582
self.arm_vehicle()
4583
post_armed_list = self.log_list()
4584
if len(post_armed_list) - len(post_disarmed_post_delay_list) != 1:
4585
raise NotAchievedException("Did not get new log for rotation")
4586
self.progress("Now checking natural rotation after HAL_LOGGER_ARM_PERSIST")
4587
self.disarm_vehicle()
4588
post_disarmed_list = self.log_list()
4589
if len(post_disarmed_list) != len(post_armed_list):
4590
raise NotAchievedException("Log rotated immediately")
4591
self.delay_sim_time(30)
4592
delayed_post_disarmed_list = self.log_list()
4593
# should *still* not get another log as LOG_DISARMED is false
4594
if len(post_disarmed_list) != len(delayed_post_disarmed_list):
4595
self.progress("Unexpected new log found")
4596
4597
def onboard_logging_log_disarmed(self):
4598
self.start_subtest("Test LOG_DISARMED-is-true behaviour")
4599
start_list = self.log_list()
4600
self.set_parameter("LOG_FILE_DSRMROT", 0)
4601
self.set_parameter("LOG_DISARMED", 0)
4602
self.reboot_sitl()
4603
restart_list = self.log_list()
4604
if len(start_list) != len(restart_list):
4605
raise NotAchievedException(
4606
"Unexpected log detected (pre-delay) initial=(%s) restart=(%s)" %
4607
(str(sorted(start_list)), str(sorted(restart_list))))
4608
self.delay_sim_time(20)
4609
restart_list = self.log_list()
4610
if len(start_list) != len(restart_list):
4611
raise NotAchievedException("Unexpected log detected (post-delay)")
4612
self.set_parameter("LOG_DISARMED", 1)
4613
self.delay_sim_time(5) # LOG_DISARMED is polled
4614
post_log_disarmed_set_list = self.log_list()
4615
if len(post_log_disarmed_set_list) == len(restart_list):
4616
raise NotAchievedException("Did not get new log when LOG_DISARMED set")
4617
self.progress("Ensuring we get a new log after a reboot")
4618
self.reboot_sitl()
4619
self.delay_sim_time(5)
4620
post_reboot_log_list = self.log_list()
4621
if len(post_reboot_log_list) == len(post_log_disarmed_set_list):
4622
raise NotAchievedException("Did not get fresh log-disarmed log after a reboot")
4623
self.progress("Ensuring no log rotation when we toggle LOG_DISARMED off then on again")
4624
self.set_parameter("LOG_DISARMED", 0)
4625
current_log_filepath = self.current_onboard_log_filepath()
4626
self.delay_sim_time(10) # LOG_DISARMED is polled
4627
post_toggleoff_list = self.log_list()
4628
if len(post_toggleoff_list) != len(post_reboot_log_list):
4629
raise NotAchievedException("Shouldn't get new file yet")
4630
self.progress("Ensuring log does not grow when LOG_DISARMED unset...")
4631
current_log_filepath_size = os.path.getsize(current_log_filepath)
4632
self.delay_sim_time(5)
4633
current_log_filepath_new_size = os.path.getsize(current_log_filepath)
4634
if current_log_filepath_new_size != current_log_filepath_size:
4635
raise NotAchievedException(
4636
"File growing after LOG_DISARMED unset (new=%u old=%u" %
4637
(current_log_filepath_new_size, current_log_filepath_size))
4638
self.progress("Turning LOG_DISARMED back on again")
4639
self.set_parameter("LOG_DISARMED", 1)
4640
self.delay_sim_time(5) # LOG_DISARMED is polled
4641
post_toggleon_list = self.log_list()
4642
if len(post_toggleon_list) != len(post_toggleoff_list):
4643
raise NotAchievedException("Log rotated when it shouldn't")
4644
self.progress("Checking log is now growing again")
4645
if os.path.getsize(current_log_filepath) == current_log_filepath_size:
4646
raise NotAchievedException("Log is not growing")
4647
4648
# self.progress("Checking LOG_FILE_DSRMROT behaviour when log_DISARMED set")
4649
# self.set_parameter("LOG_FILE_DSRMROT", 1)
4650
# self.wait_ready_to_arm()
4651
# pre = self.log_list()
4652
# self.arm_vehicle()
4653
# post = self.log_list()
4654
# if len(pre) != len(post):
4655
# raise NotAchievedException("Rotation happened on arming?!")
4656
# size_a = os.path.getsize(current_log_filepath)
4657
# self.delay_sim_time(5)
4658
# size_b = os.path.getsize(current_log_filepath)
4659
# if size_b <= size_a:
4660
# raise NotAchievedException("Log not growing")
4661
# self.disarm_vehicle()
4662
# instant_post_disarm_list = self.log_list()
4663
# self.progress("Should not rotate straight away")
4664
# if len(instant_post_disarm_list) != len(post):
4665
# raise NotAchievedException("Should not rotate straight away")
4666
# self.delay_sim_time(20)
4667
# post_disarm_list = self.log_list()
4668
# if len(post_disarm_list) - len(instant_post_disarm_list) != 1:
4669
# raise NotAchievedException("Did not get exactly one more log")
4670
4671
# self.progress("If we re-arm during the HAL_LOGGER_ARM_PERSIST period it should rotate")
4672
4673
def onboard_logging_forced_arm(self):
4674
'''ensure a bug where we didn't start logging when arming was forced
4675
does not reappear'''
4676
self.start_subtest("Ensure we get a log when force-arming")
4677
self.set_parameter("LOG_DISARMED", 0)
4678
self.reboot_sitl() # so we'll definitely start a log on arming
4679
pre_arming_list = self.log_list()
4680
self.wait_ready_to_arm()
4681
self.arm_vehicle(force=True)
4682
# we might be relying on a thread to actually create the log
4683
# file when doing forced-arming; give the file time to appear:
4684
self.delay_sim_time(10)
4685
post_arming_list = self.log_list()
4686
self.disarm_vehicle()
4687
if len(post_arming_list) <= len(pre_arming_list):
4688
raise NotAchievedException("Did not get a log on forced arm")
4689
4690
def Logging(self):
4691
'''Test Onboard Logging'''
4692
if self.is_tracker():
4693
return
4694
self.onboard_logging_forced_arm()
4695
self.onboard_logging_log_disarmed()
4696
self.onboard_logging_not_log_disarmed()
4697
4698
def LoggingFormatSanityChecks(self, path):
4699
dfreader = self.dfreader_for_path(path)
4700
first_message = dfreader.recv_match()
4701
if first_message.get_type() != 'FMT':
4702
raise NotAchievedException("Expected first message to be a FMT message")
4703
if first_message.Name != 'FMT':
4704
raise NotAchievedException("Expected first message to be the FMT FMT message")
4705
4706
self.progress("Ensuring DCM format is received") # it's a WriteStreaming message...
4707
while True:
4708
m = dfreader.recv_match(type='FMT')
4709
if m is None:
4710
raise NotAchievedException("Did not find DCM format")
4711
if m.Name != 'DCM':
4712
continue
4713
self.progress("Found DCM format")
4714
break
4715
4716
self.progress("No message should appear before its format")
4717
dfreader.rewind()
4718
seen_formats = set()
4719
while True:
4720
m = dfreader.recv_match()
4721
if m is None:
4722
break
4723
m_type = m.get_type()
4724
if m_type == 'FMT':
4725
seen_formats.add(m.Name)
4726
continue
4727
if m_type not in seen_formats:
4728
raise ValueError(f"{m_type} seen before its format")
4729
# print(f"{m_type} OK")
4730
4731
def LoggingFormat(self):
4732
'''ensure formats are emitted appropriately'''
4733
4734
self.context_push()
4735
self.set_parameter('LOG_FILE_DSRMROT', 1)
4736
self.wait_ready_to_arm()
4737
for i in range(3):
4738
self.arm_vehicle()
4739
self.delay_sim_time(5)
4740
path = self.current_onboard_log_filepath()
4741
self.disarm_vehicle()
4742
self.LoggingFormatSanityChecks(path)
4743
self.context_pop()
4744
4745
self.context_push()
4746
for i in range(3):
4747
self.set_parameter("LOG_DISARMED", 1)
4748
self.reboot_sitl()
4749
self.delay_sim_time(5)
4750
path = self.current_onboard_log_filepath()
4751
self.set_parameter("LOG_DISARMED", 0)
4752
self.LoggingFormatSanityChecks(path)
4753
self.context_pop()
4754
4755
def TestLogDownloadMAVProxy(self, upload_logs=False):
4756
"""Download latest log."""
4757
filename = "MAVProxy-downloaded-log.BIN"
4758
mavproxy = self.start_mavproxy()
4759
self.mavproxy_load_module(mavproxy, 'log')
4760
self.set_parameter('SIM_SPEEDUP', 1)
4761
mavproxy.send("log list\n")
4762
mavproxy.expect("numLogs")
4763
self.wait_heartbeat()
4764
self.wait_heartbeat()
4765
mavproxy.send("set shownoise 0\n")
4766
mavproxy.send("log download latest %s\n" % filename)
4767
mavproxy.expect("Finished downloading", timeout=120)
4768
self.mavproxy_unload_module(mavproxy, 'log')
4769
self.stop_mavproxy(mavproxy)
4770
4771
def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):
4772
"""Download latest log over network port"""
4773
self.context_push()
4774
self.set_parameters({
4775
"NET_ENABLE": 1,
4776
"LOG_DISARMED": 0,
4777
"LOG_DARM_RATEMAX": 1, # make small logs
4778
# UDP client
4779
"NET_P1_TYPE": 1,
4780
"NET_P1_PROTOCOL": 2,
4781
"NET_P1_PORT": 16001,
4782
"NET_P1_IP0": 127,
4783
"NET_P1_IP1": 0,
4784
"NET_P1_IP2": 0,
4785
"NET_P1_IP3": 1,
4786
# UDP server
4787
"NET_P2_TYPE": 2,
4788
"NET_P2_PROTOCOL": 2,
4789
"NET_P2_PORT": 16002,
4790
"NET_P2_IP0": 0,
4791
"NET_P2_IP1": 0,
4792
"NET_P2_IP2": 0,
4793
"NET_P2_IP3": 0,
4794
# TCP client
4795
"NET_P3_TYPE": 3,
4796
"NET_P3_PROTOCOL": 2,
4797
"NET_P3_PORT": 16003,
4798
"NET_P3_IP0": 127,
4799
"NET_P3_IP1": 0,
4800
"NET_P3_IP2": 0,
4801
"NET_P3_IP3": 1,
4802
# TCP server
4803
"NET_P4_TYPE": 4,
4804
"NET_P4_PROTOCOL": 2,
4805
"NET_P4_PORT": 16004,
4806
"NET_P4_IP0": 0,
4807
"NET_P4_IP1": 0,
4808
"NET_P4_IP2": 0,
4809
"NET_P4_IP3": 0,
4810
})
4811
self.reboot_sitl()
4812
4813
# ensure the latest log file is very small:
4814
self.context_push()
4815
self.set_parameter('LOG_DISARMED', 1)
4816
self.delay_sim_time(15)
4817
self.progress(f"Current onboard log filepath {self.current_onboard_log_filepath()}")
4818
self.context_pop()
4819
4820
# ensure that the autopilot has a timestamp on that file by
4821
# now, or MAVProxy does not see it as the latest log:
4822
self.wait_gps_fix_type_gte(3)
4823
4824
self.set_parameter('SIM_SPEEDUP', 1)
4825
4826
endpoints = [('UDPClient', ':16001') ,
4827
('UDPServer', 'udpout:127.0.0.1:16002'),
4828
('TCPClient', 'tcpin:0.0.0.0:16003'),
4829
('TCPServer', 'tcp:127.0.0.1:16004')]
4830
for name, e in endpoints:
4831
self.progress("Downloading log with %s %s" % (name, e))
4832
filename = "MAVProxy-downloaded-net-log-%s.BIN" % name
4833
4834
mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])
4835
self.mavproxy_load_module(mavproxy, 'log')
4836
self.wait_heartbeat()
4837
mavproxy.send("log list\n")
4838
mavproxy.expect("numLogs")
4839
# ensure the full list of logs has come out
4840
for i in range(5):
4841
self.wait_heartbeat()
4842
mavproxy.send("log download latest %s\n" % filename)
4843
mavproxy.expect("Finished downloading", timeout=120)
4844
self.mavproxy_unload_module(mavproxy, 'log')
4845
self.stop_mavproxy(mavproxy)
4846
4847
self.set_parameters({
4848
# multicast UDP client
4849
"NET_P1_TYPE": 1,
4850
"NET_P1_PROTOCOL": 2,
4851
"NET_P1_PORT": 16005,
4852
"NET_P1_IP0": 239,
4853
"NET_P1_IP1": 255,
4854
"NET_P1_IP2": 145,
4855
"NET_P1_IP3": 50,
4856
# Broadcast UDP client
4857
"NET_P2_TYPE": 1,
4858
"NET_P2_PROTOCOL": 2,
4859
"NET_P2_PORT": 16006,
4860
"NET_P2_IP0": 255,
4861
"NET_P2_IP1": 255,
4862
"NET_P2_IP2": 255,
4863
"NET_P2_IP3": 255,
4864
"NET_P3_TYPE": -1,
4865
"NET_P4_TYPE": -1,
4866
"LOG_DISARMED": 0,
4867
})
4868
self.reboot_sitl()
4869
4870
self.set_parameter('SIM_SPEEDUP', 1)
4871
4872
endpoints = [('UDPMulticast', 'mcast:16005') ,
4873
('UDPBroadcast', ':16006')]
4874
for name, e in endpoints:
4875
self.progress("Downloading log with %s %s" % (name, e))
4876
filename = "MAVProxy-downloaded-net-log-%s.BIN" % name
4877
4878
mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])
4879
self.mavproxy_load_module(mavproxy, 'log')
4880
self.wait_heartbeat()
4881
mavproxy.send("log list\n")
4882
mavproxy.expect("numLogs")
4883
# ensure the full list of logs has come out
4884
for i in range(5):
4885
self.wait_heartbeat()
4886
mavproxy.send("log download latest %s\n" % filename)
4887
mavproxy.expect("Finished downloading", timeout=120)
4888
self.mavproxy_unload_module(mavproxy, 'log')
4889
self.stop_mavproxy(mavproxy)
4890
4891
self.context_pop()
4892
4893
def TestLogDownloadMAVProxyCAN(self, upload_logs=False):
4894
"""Download latest log over CAN serial port"""
4895
self.context_push()
4896
self.set_parameters({
4897
"CAN_P1_DRIVER": 1,
4898
"LOG_DISARMED": 1,
4899
})
4900
self.reboot_sitl()
4901
self.set_parameters({
4902
"CAN_D1_UC_SER_EN": 1,
4903
"CAN_D1_UC_S1_NOD": 125,
4904
"CAN_D1_UC_S1_IDX": 4,
4905
"CAN_D1_UC_S1_BD": 57600,
4906
"CAN_D1_UC_S1_PRO": 2,
4907
})
4908
self.reboot_sitl()
4909
4910
self.set_parameter('SIM_SPEEDUP', 1)
4911
4912
filename = "MAVProxy-downloaded-can-log.BIN"
4913
# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:15550
4914
mavproxy = self.start_mavproxy(master=':15550')
4915
mavproxy.expect("Detected vehicle")
4916
self.mavproxy_load_module(mavproxy, 'log')
4917
mavproxy.send("log list\n")
4918
mavproxy.expect("numLogs")
4919
# ensure the full list of logs has come out
4920
for i in range(5):
4921
self.wait_heartbeat()
4922
mavproxy.send("set shownoise 0\n")
4923
mavproxy.send("log download latest %s\n" % filename)
4924
mavproxy.expect("Finished downloading", timeout=120)
4925
self.mavproxy_unload_module(mavproxy, 'log')
4926
self.stop_mavproxy(mavproxy)
4927
self.context_pop()
4928
4929
def show_gps_and_sim_positions(self, on_off):
4930
"""Allow to display gps and actual position on map."""
4931
if on_off is True:
4932
# turn on simulator display of gps and actual position
4933
self.mavproxy.send('map set showgpspos 1\n')
4934
self.mavproxy.send('map set showsimpos 1\n')
4935
else:
4936
# turn off simulator display of gps and actual position
4937
self.mavproxy.send('map set showgpspos 0\n')
4938
self.mavproxy.send('map set showsimpos 0\n')
4939
4940
@staticmethod
4941
def mission_count(filename):
4942
"""Load a mission from a file and return number of waypoints."""
4943
wploader = mavwp.MAVWPLoader()
4944
wploader.load(filename)
4945
return wploader.count()
4946
4947
def install_message_hook(self, hook):
4948
self.message_hooks.append(hook)
4949
4950
def install_message_hook_context(self, hook):
4951
'''installs a message hook which will be removed when the context goes
4952
away'''
4953
if self.mav is None:
4954
return
4955
self.message_hooks.append(hook)
4956
self.context_get().message_hooks.append(hook)
4957
4958
def remove_message_hook(self, hook):
4959
'''remove hook from list of message hooks. Assumes it exists exactly
4960
once'''
4961
if self.mav is None:
4962
return
4963
self.message_hooks.remove(hook)
4964
if isinstance(hook, TestSuite.MessageHook):
4965
hook.hook_removed()
4966
4967
def install_script_content_context(self, scriptname, content):
4968
'''installs an example script with content which will be
4969
removed when the context goes away
4970
'''
4971
self.install_script_content(scriptname, content)
4972
self.context_get().installed_scripts.append(scriptname)
4973
4974
def install_example_script_context(self, scriptname):
4975
'''installs an example script which will be removed when the context goes
4976
away'''
4977
self.install_example_script(scriptname)
4978
self.context_get().installed_scripts.append(scriptname)
4979
4980
def install_test_script_context(self, scriptnames):
4981
'''installs an test script which will be removed when the context goes
4982
away'''
4983
if isinstance(scriptnames, str):
4984
scriptnames = [scriptnames]
4985
for scriptname in scriptnames:
4986
self.install_test_script(scriptname)
4987
self.context_get().installed_scripts.extend(scriptnames)
4988
4989
def install_test_scripts_context(self, *args, **kwargs):
4990
'''same as install_test_scripts_context - just pluralised name'''
4991
return self.install_test_script_context(*args, **kwargs)
4992
4993
def install_test_modules_context(self):
4994
'''installs test modules which will be removed when the context goes
4995
away'''
4996
self.install_test_modules()
4997
self.context_get().installed_modules.append("test")
4998
4999
def install_mavlink_module_context(self):
5000
'''installs mavlink module which will be removed when the context goes
5001
away'''
5002
self.install_mavlink_module()
5003
self.context_get().installed_modules.append("mavlink")
5004
5005
def install_applet_script_context(self, scriptname, **kwargs):
5006
'''installs an applet script which will be removed when the context goes
5007
away'''
5008
self.install_applet_script(scriptname, **kwargs)
5009
self.context_get().installed_scripts.append(scriptname)
5010
5011
def rootdir(self):
5012
this_dir = os.path.dirname(__file__)
5013
return os.path.realpath(os.path.join(this_dir, "../.."))
5014
5015
def ardupilot_stores_frame_for_cmd(self, t):
5016
# ardupilot doesn't remember frame on these commands
5017
return t not in [
5018
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
5019
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
5020
mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
5021
mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,
5022
mavutil.mavlink.MAV_CMD_DO_JUMP,
5023
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
5024
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
5025
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
5026
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
5027
]
5028
5029
def assert_mission_files_same(self, file1, file2, match_comments=False):
5030
self.progress("Comparing (%s) and (%s)" % (file1, file2, ))
5031
5032
f1 = open(file1)
5033
f2 = open(file2)
5034
lines1 = f1.readlines()
5035
lines2 = f2.readlines()
5036
5037
if not match_comments:
5038
# strip comments from all lines
5039
lines1 = [re.sub(r"\s*#.*", "", x) for x in lines1]
5040
lines2 = [re.sub(r"\s*#.*", "", x) for x in lines2]
5041
lines1 = [x.rstrip() for x in lines1]
5042
lines2 = [x.rstrip() for x in lines2]
5043
# remove now-empty lines:
5044
lines1 = filter(lambda x: len(x), lines1)
5045
lines2 = filter(lambda x: len(x), lines2)
5046
5047
for l1, l2 in zip(lines1, lines2):
5048
l1 = l1.rstrip("\r\n")
5049
l2 = l2.rstrip("\r\n")
5050
if l1 == l2:
5051
# e.g. the first "QGC WPL 110" line
5052
continue
5053
if re.match(r"0\s", l1):
5054
# home changes...
5055
continue
5056
l1 = l1.rstrip()
5057
l2 = l2.rstrip()
5058
fields1 = re.split(r"\s+", l1)
5059
fields2 = re.split(r"\s+", l2)
5060
# line = int(fields1[0])
5061
t = int(fields1[3]) # mission item type
5062
for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):
5063
if count == 2: # frame
5064
if not self.ardupilot_stores_frame_for_cmd(t):
5065
if int(i1) in [3, 10]: # 3 is relative, 10 is terrain
5066
i1 = 0
5067
if int(i2) in [3, 10]:
5068
i2 = 0
5069
if count == 6: # param 3
5070
if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:
5071
# ardupilot canonicalises this to -1 for ccw or 1 for cw.
5072
if float(i1) == 0:
5073
i1 = 1.0
5074
if float(i2) == 0:
5075
i2 = 1.0
5076
if count == 7: # param 4
5077
if t == mavutil.mavlink.MAV_CMD_NAV_LAND:
5078
# ardupilot canonicalises "0" to "1" param 4 (yaw)
5079
if int(float(i1)) == 0:
5080
i1 = 1
5081
if int(float(i2)) == 0:
5082
i2 = 1
5083
if 0 <= count <= 3 or 11 <= count <= 11:
5084
if int(i1) != int(i2):
5085
raise ValueError("Files have different content: (%s vs %s) (%s vs %s) (%d vs %d) (count=%u)" %
5086
(file1, file2, l1, l2, int(i1), int(i2), count)) # NOCI
5087
continue
5088
if 4 <= count <= 10:
5089
f_i1 = float(i1)
5090
f_i2 = float(i2)
5091
delta = abs(f_i1 - f_i2)
5092
max_allowed_delta = 0.000009
5093
if delta > max_allowed_delta:
5094
raise ValueError(
5095
("Files have different (float) content: " +
5096
"(%s) and (%s) " +
5097
"(%s vs %s) " +
5098
"(%f vs %f) " +
5099
"(%.10f) " +
5100
"(count=%u)") %
5101
(file1, file2,
5102
l1, l2,
5103
f_i1, f_i2,
5104
delta,
5105
count)) # NOCI
5106
continue
5107
raise ValueError("count %u not handled" % count)
5108
self.progress("Files same")
5109
5110
def assert_not_receive_message(self, message, timeout=1, mav=None, condition=None):
5111
'''this is like assert_not_receiving_message but uses sim time not
5112
wallclock time'''
5113
self.progress("making sure we're not getting %s messages" % message)
5114
if mav is None:
5115
mav = self.mav
5116
5117
tstart = self.get_sim_time_cached()
5118
while True:
5119
m = mav.recv_match(type=message, blocking=True, timeout=0.1, condition=condition)
5120
if m is not None:
5121
self.progress("Received: %s" % self.dump_message_verbose(m))
5122
raise PreconditionFailedException("Receiving %s messages" % message)
5123
if mav != self.mav:
5124
# update timestamp....
5125
self.drain_mav(self.mav)
5126
if self.get_sim_time_cached() - tstart > timeout:
5127
return
5128
5129
def assert_receive_message(self,
5130
type,
5131
timeout=None,
5132
verbose=False,
5133
very_verbose=False,
5134
mav=None,
5135
condition=None,
5136
delay_fn=None,
5137
instance=None,
5138
check_context=False):
5139
if timeout is None:
5140
timeout = 1
5141
if mav is None:
5142
mav = self.mav
5143
5144
if check_context:
5145
collection = self.context_collection(type)
5146
if len(collection) > 0:
5147
# return the most-recently-received message:
5148
return collection[-1]
5149
5150
m = None
5151
tstart = time.time() # timeout in wallclock
5152
while True:
5153
m = mav.recv_match(type=type, blocking=True, timeout=0.05, condition=condition)
5154
if instance is not None:
5155
if getattr(m, m._instance_field) != instance:
5156
continue
5157
if m is not None:
5158
break
5159
elapsed_time = time.time() - tstart
5160
if elapsed_time > timeout:
5161
raise NotAchievedException("Did not get %s after %s seconds" %
5162
(type, elapsed_time))
5163
if delay_fn is not None:
5164
delay_fn()
5165
if verbose:
5166
self.progress("Received (%s)" % str(m))
5167
if very_verbose:
5168
self.progress(self.dump_message_verbose(m))
5169
return m
5170
5171
def assert_receive_named_value_float(self, name, timeout=10):
5172
tstart = self.get_sim_time_cached()
5173
while True:
5174
if self.get_sim_time_cached() - tstart > timeout:
5175
raise NotAchievedException("Did not get NAMED_VALUE_FLOAT %s" % name)
5176
m = self.assert_receive_message('NAMED_VALUE_FLOAT', verbose=1, very_verbose=1, timeout=timeout)
5177
if m.name != name:
5178
continue
5179
return m
5180
5181
def assert_receive_named_value_float_value(self, name, value, epsilon=0.0001, timeout=10):
5182
m = self.assert_receive_named_value_float_value(name, timeout=timeout)
5183
if abs(m.value - value) > epsilon:
5184
raise NotAchievedException("Bad %s want=%f got=%f" % (name, value, m.value))
5185
5186
def assert_rally_files_same(self, file1, file2):
5187
self.progress("Comparing (%s) and (%s)" % (file1, file2, ))
5188
f1 = open(file1)
5189
f2 = open(file2)
5190
lines_f1 = f1.readlines()
5191
lines_f2 = f2.readlines()
5192
self.assert_rally_content_same(lines_f1, lines_f2)
5193
5194
def assert_rally_filepath_content(self, file1, content):
5195
f1 = open(file1)
5196
lines_f1 = f1.readlines()
5197
lines_content = content.split("\n")
5198
print("lines content: %s" % str(lines_content))
5199
self.assert_rally_content_same(lines_f1, lines_content)
5200
5201
def assert_rally_content_same(self, f1, f2):
5202
'''check each line in f1 matches one-to-one with f2'''
5203
for l1, l2 in zip(f1, f2):
5204
print("l1: %s" % l1)
5205
print("l2: %s" % l2)
5206
l1 = l1.rstrip("\n")
5207
l2 = l2.rstrip("\n")
5208
l1 = l1.rstrip("\r")
5209
l2 = l2.rstrip("\r")
5210
if l1 == l2:
5211
# e.g. the first "QGC WPL 110" line
5212
continue
5213
l1 = l1.rstrip()
5214
l2 = l2.rstrip()
5215
print("al1: %s" % str(l1))
5216
print("al2: %s" % str(l2))
5217
fields1 = re.split(r"\s+", l1)
5218
fields2 = re.split(r"\s+", l2)
5219
# line = int(fields1[0])
5220
# t = int(fields1[3]) # mission item type
5221
for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):
5222
self.progress(f"{count=} {i1=} {i2=}")
5223
if 0 <= count <= 3 or 11 <= count <= 11:
5224
if int(i1) != int(i2):
5225
raise ValueError(
5226
"Rally points different: "
5227
f"({l1} vs {l2}) " +
5228
f"{int(i1)} vs {int(i2)}) " +
5229
f"({count=}))"
5230
)
5231
continue
5232
if 4 <= count <= 10:
5233
f_i1 = float(i1)
5234
f_i2 = float(i2)
5235
delta = abs(f_i1 - f_i2)
5236
max_allowed_delta = 0.000009
5237
self.progress(f"{count=} {f_i1=} {f_i2=}")
5238
if delta > max_allowed_delta:
5239
raise ValueError(
5240
"Rally has different (float) content: " +
5241
f"({l1} vs {l2}) " +
5242
f"({f_i1} vs {f_i2}) " +
5243
f"({delta:.10f}) " +
5244
f"({count=})")
5245
continue
5246
raise ValueError("count %u not handled" % count)
5247
self.progress("Rally content same")
5248
5249
def load_rally_using_mavproxy(self, filename):
5250
"""Load rally points from a file to flight controller."""
5251
self.progress("Loading rally points (%s)" % filename)
5252
path = os.path.join(testdir, self.current_test_name_directory, filename)
5253
mavproxy = self.start_mavproxy()
5254
mavproxy.send('rally load %s\n' % path)
5255
mavproxy.expect("Loaded")
5256
self.delay_sim_time(10) # allow transfer to complete
5257
self.stop_mavproxy(mavproxy)
5258
5259
def load_sample_mission(self):
5260
self.load_mission(self.sample_mission_filename())
5261
5262
def generic_mission_filepath_for_filename(self, filename):
5263
return os.path.join(testdir, "Generic_Missions", filename)
5264
5265
def load_generic_mission(self, filename, strict=True):
5266
return self.load_mission_from_filepath(
5267
self.generic_mission_filepath_for_filename(filename),
5268
strict=strict)
5269
5270
def load_mission(self, filename, strict=True):
5271
return self.load_mission_from_filepath(
5272
os.path.join(testdir, self.current_test_name_directory, filename),
5273
strict=strict)
5274
5275
def wp_to_mission_item_int(self, wp, mission_type):
5276
'''convert a MISSION_ITEM to a MISSION_ITEM_INT. We always send as
5277
MISSION_ITEM_INT to give cm level accuracy
5278
Swiped from mavproxy_wp.py
5279
'''
5280
if wp.get_type() == 'MISSION_ITEM_INT':
5281
return wp
5282
wp_int = mavutil.mavlink.MAVLink_mission_item_int_message(
5283
wp.target_system,
5284
wp.target_component,
5285
wp.seq,
5286
wp.frame,
5287
wp.command,
5288
wp.current,
5289
wp.autocontinue,
5290
wp.param1,
5291
wp.param2,
5292
wp.param3,
5293
wp.param4,
5294
int(wp.x*1.0e7),
5295
int(wp.y*1.0e7),
5296
wp.z,
5297
mission_type,
5298
)
5299
return wp_int
5300
5301
def mission_item_protocol_items_from_filepath(self,
5302
loaderclass,
5303
filepath,
5304
target_system=1,
5305
target_component=1,
5306
):
5307
'''returns a list of mission-item-ints from filepath'''
5308
# self.progress("filepath: %s" % filepath)
5309
wploader = loaderclass(
5310
target_system=target_system,
5311
target_component=target_component
5312
)
5313
itemstype = mavutil.mavlink.enums["MAV_MISSION_TYPE"][wploader.mav_mission_type()].name
5314
self.progress(f"Loading {itemstype} ({os.path.basename(filepath)})")
5315
wploader.load(filepath)
5316
return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:502
5317
5318
def mission_from_filepath(self, filepath, target_system=1, target_component=1):
5319
'''returns a list of mission-item-ints from filepath'''
5320
return self.mission_item_protocol_items_from_filepath(
5321
mavwp.MAVWPLoader,
5322
filepath,
5323
target_system=target_system,
5324
target_component=target_component,
5325
)
5326
5327
def sitl_home_string_from_mission(self, filename):
5328
'''return a string of the form "lat,lng,yaw,alt" from the home
5329
location in a mission file'''
5330
return "%s,%s,%s,%s" % self.get_home_tuple_from_mission(filename)
5331
5332
def sitl_home_string_from_mission_filepath(self, filepath):
5333
'''return a string of the form "lat,lng,yaw,alt" from the home
5334
location in a mission file'''
5335
return "%s,%s,%s,%s" % self.get_home_tuple_from_mission_filepath(filepath)
5336
5337
def get_home_tuple_from_mission(self, filename):
5338
'''gets item 0 from the mission file, returns a tuple suitable for
5339
passing to customise_SITL_commandline as --home. Yaw will be
5340
0, so the caller may want to fill that in
5341
'''
5342
return self.get_home_tuple_from_mission_filepath(
5343
os.path.join(testdir, self.current_test_name_directory, filename)
5344
)
5345
5346
def get_home_location_from_mission(self, filename):
5347
(home_lat, home_lon, home_alt, heading) = self.get_home_tuple_from_mission("rover-path-planning-mission.txt")
5348
return mavutil.location(home_lat, home_lon)
5349
5350
def get_home_tuple_from_mission_filepath(self, filepath):
5351
'''gets item 0 from the mission file, returns a tuple suitable for
5352
passing to customise_SITL_commandline as --home. Yaw will be
5353
0, so the caller may want to fill that in
5354
'''
5355
items = self.mission_from_filepath(filepath)
5356
home_item = items[0]
5357
return (home_item.x * 1e-7, home_item.y * 1e-7, home_item.z, 0)
5358
5359
# TODO: rename the following to "upload_mission_from_filepath"
5360
def load_mission_from_filepath(self,
5361
filepath,
5362
target_system=1,
5363
target_component=1,
5364
strict=True,
5365
reset_current_wp=True):
5366
wpoints_int = self.mission_from_filepath(
5367
filepath,
5368
target_system=target_system,
5369
target_component=target_component
5370
)
5371
self.check_mission_upload_download(wpoints_int, strict=strict)
5372
if reset_current_wp:
5373
# ArduPilot doesn't reset the current waypoint by default
5374
# we may be in auto mode and running waypoints, so we
5375
# can't check the current waypoint after resetting it.
5376
self.set_current_waypoint(0, check_afterwards=False)
5377
return len(wpoints_int)
5378
5379
def load_mission_using_mavproxy(self, mavproxy, filename):
5380
return self.load_mission_from_filepath_using_mavproxy(
5381
mavproxy,
5382
self.current_test_name_directory,
5383
filename)
5384
5385
def load_mission_from_filepath_using_mavproxy(self,
5386
mavproxy,
5387
filepath,
5388
filename):
5389
"""Load a mission from a file to flight controller."""
5390
self.progress("Loading mission (%s)" % filename)
5391
path = os.path.join(testdir, filepath, filename)
5392
tstart = self.get_sim_time()
5393
while True:
5394
t2 = self.get_sim_time()
5395
if t2 - tstart > 10:
5396
raise AutoTestTimeoutException("Failed to do waypoint thing")
5397
# the following hack is to get around MAVProxy statustext deduping:
5398
while time.time() - self.last_wp_load < 3:
5399
self.progress("Waiting for MAVProxy de-dupe timer to expire")
5400
self.drain_mav()
5401
time.sleep(0.1)
5402
mavproxy.send('wp load %s\n' % path)
5403
mavproxy.expect('Loaded ([0-9]+) waypoints from')
5404
load_count = mavproxy.match.group(1)
5405
self.last_wp_load = time.time()
5406
mavproxy.expect("Flight plan received")
5407
mavproxy.send('wp list\n')
5408
mavproxy.expect('Requesting ([0-9]+) waypoints')
5409
request_count = mavproxy.match.group(1)
5410
if load_count != request_count:
5411
self.progress("request_count=%s != load_count=%s" %
5412
(request_count, load_count))
5413
continue
5414
mavproxy.expect('Saved ([0-9]+) waypoints to (.+?way.txt)')
5415
save_count = mavproxy.match.group(1)
5416
if save_count != request_count:
5417
raise NotAchievedException("request count != load count")
5418
# warning: this assumes MAVProxy was started in the CWD!
5419
# on the autotest server we invoke autotest.py one-up from
5420
# the git root, like this:
5421
# timelimit 32000 APM/Tools/autotest/autotest.py --timeout=30000 > buildlogs/autotest-output.txt 2>&1
5422
# that means the MAVProxy log files are not reltopdir!
5423
saved_filepath = mavproxy.match.group(2)
5424
saved_filepath = saved_filepath.rstrip()
5425
self.assert_mission_files_same(path, saved_filepath)
5426
break
5427
mavproxy.send('wp status\n')
5428
mavproxy.expect(r'Have (\d+) of (\d+)')
5429
status_have = mavproxy.match.group(1)
5430
status_want = mavproxy.match.group(2)
5431
if status_have != status_want:
5432
raise ValueError("status count mismatch")
5433
if status_have != save_count:
5434
raise ValueError("status have not equal to save count")
5435
5436
wploader = mavwp.MAVWPLoader()
5437
wploader.load(path)
5438
num_wp = wploader.count()
5439
if num_wp != int(status_have):
5440
raise ValueError("num_wp=%u != status_have=%u" %
5441
(num_wp, int(status_have)))
5442
if num_wp == 0:
5443
raise ValueError("No waypoints loaded?!")
5444
5445
return num_wp
5446
5447
def save_mission_to_file_using_mavproxy(self, mavproxy, filename):
5448
"""Save a mission to a file"""
5449
mavproxy.send('wp list\n')
5450
mavproxy.expect('Requesting [0-9]+ waypoints')
5451
mavproxy.send('wp save %s\n' % filename)
5452
mavproxy.expect('Saved ([0-9]+) waypoints')
5453
num_wp = int(mavproxy.match.group(1))
5454
self.progress("num_wp: %d" % num_wp)
5455
return num_wp
5456
5457
def string_for_frame(self, frame):
5458
return mavutil.mavlink.enums["MAV_FRAME"][frame].name
5459
5460
def frames_equivalent(self, f1, f2):
5461
pairs = [
5462
(mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
5463
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT),
5464
(mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5465
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT),
5466
(mavutil.mavlink.MAV_FRAME_GLOBAL,
5467
mavutil.mavlink.MAV_FRAME_GLOBAL_INT),
5468
]
5469
for pair in pairs:
5470
if (f1 == pair[0] and f2 == pair[1]):
5471
return True
5472
if (f1 == pair[1] and f2 == pair[0]):
5473
return True
5474
return f1 == f2
5475
5476
def check_mission_items_same(self,
5477
check_atts,
5478
want,
5479
got,
5480
epsilon=None,
5481
skip_first_item=False,
5482
strict=True):
5483
self.progress("Checking mission items same")
5484
if epsilon is None:
5485
epsilon = 1
5486
if len(want) != len(got):
5487
raise NotAchievedException("Incorrect item count (want=%u got=%u)" % (len(want), len(got)))
5488
self.progress("Checking %u items" % len(want))
5489
for i in range(0, len(want)):
5490
if skip_first_item and i == 0:
5491
continue
5492
item = want[i]
5493
downloaded_item = got[i]
5494
5495
check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']
5496
# z is not preserved
5497
5498
self.progress("Comparing (%s) and (%s)" % (str(item), str(downloaded_item)))
5499
5500
for att in check_atts:
5501
item_val = getattr(item, att)
5502
downloaded_item_val = getattr(downloaded_item, att)
5503
if abs(item_val - downloaded_item_val) > epsilon:
5504
raise NotAchievedException(
5505
"Item %u (%s) has different %s after download want=%s got=%s (got-item=%s)" %
5506
(i, str(item), att, str(item_val), str(downloaded_item_val), str(downloaded_item)))
5507
# for waypoint items ensure z and frame are preserved:
5508
self.progress("Type is %u" % got[0].mission_type)
5509
if got[0].mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
5510
item_val = getattr(item, 'frame')
5511
downloaded_item_val = getattr(downloaded_item, 'frame')
5512
# if you are thinking of adding another, "don't annoy
5513
# me, I know missions aren't troundtripped" non-strict
5514
# thing here, DON'T do it without first checking "def
5515
# assert_mission_files_same"; it makes the same checks
5516
# as will be needed here eventually.
5517
if ((strict or self.ardupilot_stores_frame_for_cmd(getattr(item, 'command'))) and
5518
not self.frames_equivalent(item_val, downloaded_item_val)):
5519
raise NotAchievedException("Frame not same (got=%s want=%s)" %
5520
(self.string_for_frame(downloaded_item_val),
5521
self.string_for_frame(item_val)))
5522
if downloaded_item.z == 0:
5523
delta = abs(item.z)
5524
else:
5525
delta = 1 - abs(item.z / downloaded_item.z)
5526
if delta > 0.01: # error should be less than 1 mm, but float precision issues in Python...
5527
raise NotAchievedException("Z not preserved (got=%f want=%f delta=%f%%)" %
5528
(downloaded_item.z, item.z, delta))
5529
5530
def check_fence_items_same(self, want, got, strict=True):
5531
check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']
5532
return self.check_mission_items_same(check_atts, want, got, strict=strict)
5533
5534
def check_mission_waypoint_items_same(self, want, got, strict=True):
5535
check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']
5536
return self.check_mission_items_same(check_atts, want, got, skip_first_item=True, strict=strict)
5537
5538
def check_mission_item_upload_download(self, items, itype, mission_type, strict=True):
5539
self.progress("check %s upload/download: upload %u items" %
5540
(itype, len(items),))
5541
self.upload_using_mission_protocol(mission_type, items)
5542
self.progress("check %s upload/download: download items" % itype)
5543
downloaded_items = self.download_using_mission_protocol(mission_type)
5544
if len(items) != len(downloaded_items):
5545
raise NotAchievedException("Did not download same number of items as uploaded want=%u got=%u" %
5546
(len(items), len(downloaded_items)))
5547
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_FENCE:
5548
self.check_fence_items_same(items, downloaded_items, strict=strict)
5549
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
5550
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
5551
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY:
5552
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
5553
else:
5554
raise NotAchievedException("Unhandled")
5555
5556
def check_fence_upload_download(self, items):
5557
self.check_mission_item_upload_download(
5558
items,
5559
"fence",
5560
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
5561
if self.use_map and self.mavproxy is not None:
5562
self.mavproxy.send('fence list\n')
5563
5564
def check_mission_upload_download(self, items, strict=True):
5565
self.check_mission_item_upload_download(
5566
items,
5567
"waypoints",
5568
mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
5569
strict=strict)
5570
if self.use_map and self.mavproxy is not None:
5571
self.mavproxy.send('wp list\n')
5572
5573
def check_rally_upload_download(self, items):
5574
self.check_mission_item_upload_download(
5575
items,
5576
"rally",
5577
mavutil.mavlink.MAV_MISSION_TYPE_RALLY
5578
)
5579
if self.use_map and self.mavproxy is not None:
5580
self.mavproxy.send('rally list\n')
5581
5582
def check_dflog_message_rates(self, log_filepath, message_rates):
5583
reader = self.dfreader_for_path(log_filepath)
5584
5585
counts = {}
5586
first = None
5587
while True:
5588
m = reader.recv_match()
5589
if m is None:
5590
break
5591
if (m.fmt.instance_field is not None and
5592
getattr(m, m.fmt.instance_field) != 0):
5593
continue
5594
5595
t = m.get_type()
5596
# print("t=%s" % str(t))
5597
if t not in counts:
5598
counts[t] = 0
5599
counts[t] += 1
5600
5601
if hasattr(m, 'TimeUS'):
5602
if first is None:
5603
first = m
5604
last = m
5605
5606
if first is None:
5607
raise NotAchievedException("Did not get any messages")
5608
delta_time_us = last.TimeUS - first.TimeUS
5609
5610
for (t, want_rate) in message_rates.items():
5611
if t not in counts:
5612
raise NotAchievedException("Wanted %s but got none" % t)
5613
got_rate = float(counts[t]) / delta_time_us * 1000000
5614
self.progress(f"Got ({counts[t]}) in ({delta_time_us}us) ({got_rate}/s)")
5615
5616
if abs(want_rate - got_rate) > 5:
5617
raise NotAchievedException("Not getting %s data at wanted rate want=%f got=%f" %
5618
(t, want_rate, got_rate))
5619
5620
def generate_rate_sample_log(self, log_bitmask=None):
5621
self.context_push()
5622
params = {
5623
"LOG_DISARMED": 0,
5624
"LOG_DARM_RATEMAX": 0,
5625
"LOG_FILE_RATEMAX": 0,
5626
}
5627
if log_bitmask is not None:
5628
params["LOG_BITMASK"] = log_bitmask
5629
5630
self.set_parameters(params)
5631
self.reboot_sitl()
5632
self.wait_ready_to_arm()
5633
self.set_parameter("LOG_DISARMED", 1)
5634
self.delay_sim_time(20)
5635
self.set_parameter("LOG_DISARMED", 0)
5636
path = self.current_onboard_log_filepath()
5637
self.progress("Rate sample log (%s)" % path)
5638
self.reboot_sitl() # ensure log is rotated
5639
self.context_pop()
5640
return path
5641
5642
def rc_defaults(self):
5643
return {
5644
1: 1500,
5645
2: 1500,
5646
3: 1500,
5647
4: 1500,
5648
5: 1500,
5649
6: 1500,
5650
7: 1500,
5651
8: 1500,
5652
9: 1500,
5653
10: 1500,
5654
11: 1500,
5655
12: 1500,
5656
13: 1500,
5657
14: 1500,
5658
15: 1500,
5659
16: 1500,
5660
}
5661
5662
def set_rc_from_map(self, _map, timeout=20, quiet=False):
5663
map_copy = _map.copy()
5664
for v in map_copy.values():
5665
if not isinstance(v, int):
5666
raise NotAchievedException("RC values must be integers")
5667
self.rc_queue.put(map_copy)
5668
5669
if self.rc_thread is None:
5670
self.rc_thread = threading.Thread(target=self.rc_thread_main, name='RC')
5671
if self.rc_thread is None:
5672
raise NotAchievedException("Could not create thread")
5673
self.rc_thread.start()
5674
5675
tstart = self.get_sim_time()
5676
while True:
5677
if self.get_sim_time_cached() - tstart > timeout:
5678
raise NotAchievedException("Failed to set RC values")
5679
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=1)
5680
if m is None:
5681
continue
5682
bad_channels = ""
5683
for chan in map_copy:
5684
chan_pwm = getattr(m, "chan" + str(chan) + "_raw")
5685
if chan_pwm != map_copy[chan]:
5686
bad_channels += " (ch=%u want=%u got=%u)" % (chan, map_copy[chan], chan_pwm)
5687
break
5688
if len(bad_channels) == 0:
5689
if not quiet:
5690
self.progress("RC values good")
5691
break
5692
self.progress("RC values bad:%s" % bad_channels)
5693
if not self.rc_thread.is_alive():
5694
self.rc_thread = None
5695
raise ValueError("RC thread is dead") # FIXME: type
5696
5697
def rc_thread_main(self):
5698
chan16 = [1000] * 16
5699
5700
sitl_output = mavutil.mavudp("127.0.0.1:%u" % self.sitl_rcin_port(), input=False)
5701
buf = None
5702
5703
while True:
5704
if self.rc_thread_should_quit:
5705
break
5706
5707
# the 0.05 here means we're updating the RC values into
5708
# the autopilot at 20Hz - that's our 50Hz wallclock, , not
5709
# the autopilot's simulated 20Hz, so if speedup is 10 the
5710
# autopilot will see ~2Hz.
5711
timeout = 0.02
5712
# ... and 2Hz is too slow when we now run at 100x speedup:
5713
timeout /= (self.speedup / 10.0)
5714
5715
try:
5716
map_copy = self.rc_queue.get(timeout=timeout)
5717
5718
# 16 packed entries:
5719
for i in range(1, 17):
5720
if i in map_copy:
5721
chan16[i-1] = map_copy[i]
5722
5723
except Queue.Empty:
5724
pass
5725
5726
buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)
5727
5728
if buf is None:
5729
continue
5730
5731
sitl_output.write(buf)
5732
5733
def set_rc_default(self):
5734
"""Setup all simulated RC control to 1500."""
5735
_defaults = self.rc_defaults()
5736
self.set_rc_from_map(_defaults)
5737
5738
def check_rc_defaults(self):
5739
"""Ensure all rc outputs are at defaults"""
5740
self.do_timesync_roundtrip()
5741
_defaults = self.rc_defaults()
5742
m = self.assert_receive_message('RC_CHANNELS', timeout=5)
5743
need_set = {}
5744
for chan in _defaults:
5745
default_value = _defaults[chan]
5746
current_value = getattr(m, "chan" + str(chan) + "_raw")
5747
if default_value != current_value:
5748
self.progress("chan=%u needs resetting is=%u want=%u" %
5749
(chan, current_value, default_value))
5750
need_set[chan] = default_value
5751
self.set_rc_from_map(need_set)
5752
5753
def set_rc(self, chan, pwm, timeout=20):
5754
"""Setup a simulated RC control to a PWM value"""
5755
self.set_rc_from_map({chan: pwm}, timeout=timeout)
5756
5757
def set_servo(self, chan, pwm):
5758
"""Replicate the functionality of MAVProxy: servo set <ch> <pwm>"""
5759
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm)
5760
5761
def location_offset_ne(self, location, north, east):
5762
'''move location in metres. You probably wat offset_location_ne'''
5763
print("old: %f %f" % (location.lat, location.lng))
5764
(lat, lng) = mp_util.gps_offset(location.lat, location.lng, east, north)
5765
location.lat = lat
5766
location.lng = lng
5767
print("new: %f %f" % (location.lat, location.lng))
5768
5769
def home_relative_loc_ne(self, n, e):
5770
ret = self.home_position_as_mav_location()
5771
self.location_offset_ne(ret, n, e)
5772
return ret
5773
5774
def home_relative_loc_neu(self, n, e, u):
5775
ret = self.home_position_as_mav_location()
5776
self.location_offset_ne(ret, n, e)
5777
ret.alt += u
5778
return ret
5779
5780
def zero_throttle(self):
5781
"""Set throttle to zero."""
5782
if self.is_rover():
5783
self.set_rc(3, 1500)
5784
else:
5785
self.set_rc(3, 1000)
5786
5787
def set_output_to_max(self, chan):
5788
"""Set output to max with RC Radio taking into account REVERSED parameter."""
5789
is_reversed = self.get_parameter("RC%u_REVERSED" % chan)
5790
out_max = int(self.get_parameter("RC%u_MAX" % chan))
5791
out_min = int(self.get_parameter("RC%u_MIN" % chan))
5792
if is_reversed == 0:
5793
self.set_rc(chan, out_max)
5794
else:
5795
self.set_rc(chan, out_min)
5796
5797
def set_output_to_min(self, chan):
5798
"""Set output to min with RC Radio taking into account REVERSED parameter."""
5799
is_reversed = self.get_parameter("RC%u_REVERSED" % chan)
5800
out_max = int(self.get_parameter("RC%u_MAX" % chan))
5801
out_min = int(self.get_parameter("RC%u_MIN" % chan))
5802
if is_reversed == 0:
5803
self.set_rc(chan, out_min)
5804
else:
5805
self.set_rc(chan, out_max)
5806
5807
def set_output_to_trim(self, chan):
5808
"""Set output to trim with RC Radio."""
5809
out_trim = int(self.get_parameter("RC%u_TRIM" % chan))
5810
self.set_rc(chan, out_trim)
5811
5812
def get_stick_arming_channel(self):
5813
"""Return the Rudder channel number as set in parameter."""
5814
raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
5815
5816
def get_disarm_delay(self):
5817
"""Return disarm delay value."""
5818
raise ErrorException("Disarm delay is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
5819
5820
def arming_test_mission(self):
5821
"""Load arming test mission.
5822
This mission is used to allow to change mode to AUTO. For each vehicle
5823
it get an unlimited wait waypoint and the starting takeoff if needed."""
5824
if self.is_rover() or self.is_plane() or self.is_sub():
5825
return os.path.join(testdir, self.current_test_name_directory + "test_arming.txt")
5826
else:
5827
return None
5828
5829
def test_takeoff_check_mode(self, mode, user_takeoff=False, force_disarm=False):
5830
# stabilize check
5831
self.progress("Motor takeoff check in %s" % mode)
5832
self.change_mode(mode)
5833
self.zero_throttle()
5834
self.wait_ready_to_arm()
5835
self.context_push()
5836
self.context_collect('STATUSTEXT')
5837
self.arm_vehicle()
5838
if user_takeoff:
5839
self.run_cmd(
5840
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
5841
p7=10,
5842
)
5843
else:
5844
self.set_rc(3, 1700)
5845
# we may never see ourselves as armed in a heartbeat
5846
self.wait_statustext("Takeoff blocked: ESC RPM out of range", check_context=True)
5847
self.context_pop()
5848
self.zero_throttle()
5849
self.disarm_vehicle(force=force_disarm)
5850
self.wait_disarmed()
5851
5852
def set_safetyswitch_on(self, **kwargs):
5853
self.set_safetyswitch(1, **kwargs)
5854
5855
def set_safetyswitch_off(self, **kwargs):
5856
self.set_safetyswitch(0, **kwargs)
5857
5858
def set_safetyswitch(self, value, target_system=1, target_component=1):
5859
self.mav.mav.set_mode_send(
5860
target_system,
5861
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
5862
value)
5863
self.wait_sensor_state(
5864
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,
5865
True, not value, True,
5866
verbose=True,
5867
timeout=30
5868
)
5869
5870
def armed(self, cached=False):
5871
"""Return True if vehicle is armed and safetyoff"""
5872
m = None
5873
if cached:
5874
m = self.mav.messages.get("HEARTBEAT", None)
5875
if m is None:
5876
m = self.wait_heartbeat()
5877
return (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 0
5878
5879
def send_mavlink_arm_command(self):
5880
self.send_cmd(
5881
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5882
p1=1, # ARM
5883
)
5884
5885
def send_mavlink_disarm_command(self):
5886
self.send_cmd(
5887
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5888
p1=0, # DISARM
5889
)
5890
5891
def send_mavlink_run_prearms_command(self):
5892
self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)
5893
5894
def analog_rangefinder_parameters(self):
5895
return {
5896
"RNGFND1_TYPE": 1,
5897
"RNGFND1_MIN": 0,
5898
"RNGFND1_MAX": 40.00,
5899
"RNGFND1_SCALING": 12.12,
5900
"RNGFND1_PIN": 0,
5901
}
5902
5903
def set_analog_rangefinder_parameters(self):
5904
self.set_parameters(self.analog_rangefinder_parameters())
5905
5906
def send_debug_trap(self, timeout=6000):
5907
self.progress("Sending trap to autopilot")
5908
self.run_cmd(
5909
mavutil.mavlink.MAV_CMD_DEBUG_TRAP,
5910
p1=32451, # magic number to trap
5911
timeout=timeout,
5912
)
5913
5914
def try_arm(self, result=True, expect_msg=None, timeout=60):
5915
"""Send Arming command, wait for the expected result and statustext."""
5916
self.progress("Try arming and wait for expected result")
5917
self.drain_mav()
5918
self.run_cmd(
5919
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5920
p1=1, # ARM
5921
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,
5922
timeout=timeout,
5923
)
5924
if expect_msg is not None:
5925
self.wait_statustext(
5926
expect_msg,
5927
timeout=timeout,
5928
the_function=lambda: self.send_cmd(
5929
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5930
p1=1, # ARM
5931
target_sysid=None,
5932
target_compid=None,
5933
))
5934
5935
def arm_vehicle(self, timeout=20, force=False):
5936
"""Arm vehicle with mavlink arm message."""
5937
self.progress("Arm motors with MAVLink cmd")
5938
p2 = 0
5939
if force:
5940
p2 = 2989
5941
try:
5942
self.run_cmd(
5943
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5944
p1=1, # ARM
5945
p2=p2,
5946
timeout=timeout,
5947
)
5948
except ValueError as e:
5949
# statustexts are queued; give it a second to arrive:
5950
self.delay_sim_time(5)
5951
raise e
5952
try:
5953
self.wait_armed()
5954
except AutoTestTimeoutException:
5955
raise AutoTestTimeoutException("Failed to ARM with mavlink")
5956
return True
5957
5958
def wait_armed(self, timeout=20):
5959
tstart = self.get_sim_time()
5960
while self.get_sim_time_cached() - tstart < timeout:
5961
self.wait_heartbeat(drain_mav=False)
5962
if self.mav.motors_armed():
5963
self.progress("Motors ARMED")
5964
return
5965
raise AutoTestTimeoutException("Did not become armed")
5966
5967
def disarm_vehicle(self, timeout=60, force=False):
5968
"""Disarm vehicle with mavlink disarm message."""
5969
self.progress("Disarm motors with MAVLink cmd")
5970
p2 = 0
5971
if force:
5972
p2 = 21196 # magic force disarm value
5973
self.run_cmd(
5974
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5975
p1=0, # DISARM
5976
p2=p2,
5977
timeout=timeout,
5978
)
5979
self.wait_disarmed()
5980
5981
def disarm_vehicle_expect_fail(self):
5982
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
5983
self.progress("Disarm - expect to fail")
5984
self.run_cmd(
5985
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5986
p1=0, # DISARM
5987
timeout=10,
5988
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
5989
)
5990
self.progress("Disarm - forced")
5991
self.disarm_vehicle(force=True)
5992
5993
def wait_disarmed_default_wait_time(self):
5994
return 30
5995
5996
def wait_disarmed(self, timeout=None, tstart=None):
5997
if timeout is None:
5998
timeout = self.wait_disarmed_default_wait_time()
5999
self.progress("Waiting for DISARM")
6000
if tstart is None:
6001
tstart = self.get_sim_time()
6002
last_print_time = 0
6003
while True:
6004
now = self.get_sim_time_cached()
6005
delta = now - tstart
6006
if delta > timeout:
6007
raise AutoTestTimeoutException("Failed to DISARM within %fs" %
6008
(timeout,))
6009
if now - last_print_time > 1:
6010
self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout))
6011
last_print_time = now
6012
msg = self.wait_heartbeat(quiet=True)
6013
if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
6014
# still armed
6015
continue
6016
self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %
6017
(delta, timeout))
6018
return
6019
6020
def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'):
6021
'''wait for an attitude (degrees)'''
6022
if desroll is None and despitch is None:
6023
raise ValueError("despitch or desroll must be supplied")
6024
tstart = self.get_sim_time()
6025
while True:
6026
if self.get_sim_time_cached() - tstart > timeout:
6027
raise AutoTestTimeoutException("Failed to achieve attitude")
6028
m = self.assert_receive_message(message_type, timeout=60)
6029
roll_deg = math.degrees(m.roll)
6030
pitch_deg = math.degrees(m.pitch)
6031
self.progress("wait_att[%s]: roll=%f desroll=%s pitch=%f despitch=%s" %
6032
(message_type, roll_deg, desroll, pitch_deg, despitch))
6033
if desroll is not None and abs(roll_deg - desroll) > tolerance:
6034
continue
6035
if despitch is not None and abs(pitch_deg - despitch) > tolerance:
6036
continue
6037
return
6038
6039
def wait_attitude_quaternion(self,
6040
desroll=None,
6041
despitch=None,
6042
timeout=2,
6043
tolerance=10,
6044
message_type='ATTITUDE_QUATERNION'):
6045
'''wait for an attitude (degrees)'''
6046
if desroll is None and despitch is None:
6047
raise ValueError("despitch or desroll must be supplied")
6048
tstart = self.get_sim_time()
6049
while True:
6050
if self.get_sim_time_cached() - tstart > timeout:
6051
raise AutoTestTimeoutException("Failed to achieve (quaternion) attitude")
6052
m = self.poll_message(message_type, quiet=True)
6053
q = quaternion.Quaternion([m.q1, m.q2, m.q3, m.q4])
6054
euler = q.euler
6055
roll = euler[0]
6056
pitch = euler[1]
6057
roll_deg = math.degrees(roll)
6058
pitch_deg = math.degrees(pitch)
6059
self.progress("wait_att_quat[%s]: roll=%f desroll=%s pitch=%f despitch=%s" %
6060
(message_type, roll_deg, desroll, pitch_deg, despitch))
6061
if desroll is not None and abs(roll_deg - desroll) > tolerance:
6062
continue
6063
if despitch is not None and abs(pitch_deg - despitch) > tolerance:
6064
continue
6065
self.progress("wait_att_quat: achieved")
6066
return
6067
6068
def CPUFailsafe(self):
6069
'''Ensure we do something appropriate when the main loop stops'''
6070
# Most vehicles just disarm on failsafe
6071
# customising the SITL commandline ensures the process will
6072
# get stopped/started at the end of the test
6073
if self.frame is None:
6074
raise ValueError("Frame is none?")
6075
self.customise_SITL_commandline([])
6076
self.wait_ready_to_arm()
6077
self.arm_vehicle()
6078
self.progress("Sending enter-cpu-lockup")
6079
# when we're in CPU lockup we don't get SYSTEM_TIME messages,
6080
# so get_sim_time breaks:
6081
tstart = self.get_sim_time()
6082
self.send_cmd_enter_cpu_lockup()
6083
self.wait_disarmed(timeout=5, tstart=tstart)
6084
# we're not getting SYSTEM_TIME messages at this point.... and
6085
# we're in a weird state where the vehicle is armed but the
6086
# motors are not, and we can't disarm further because Copter
6087
# looks at whether its *motors* are armed as part of its
6088
# disarm process.
6089
self.reset_SITL_commandline()
6090
6091
def cpufailsafe_wait_servo_channel_value(self, channel, value, timeout=30):
6092
'''we get restricted messages while doing cpufailsafe, this working then'''
6093
start = time.time()
6094
while True:
6095
if time.time() - start > timeout:
6096
raise NotAchievedException("Did not achieve value")
6097
m = self.assert_receive_message('SERVO_OUTPUT_RAW')
6098
channel_field = "servo%u_raw" % channel
6099
m_value = getattr(m, channel_field, None)
6100
self.progress("Servo%u=%u want=%u" % (channel, m_value, value))
6101
if m_value == value:
6102
break
6103
6104
def plane_CPUFailsafe(self):
6105
'''In lockup Plane should copy RC inputs to RC outputs'''
6106
# customising the SITL commandline ensures the process will
6107
# get stopped/started at the end of the test
6108
self.customise_SITL_commandline([])
6109
self.wait_ready_to_arm()
6110
self.arm_vehicle()
6111
self.progress("Sending enter-cpu-lockup")
6112
# when we're in CPU lockup we don't get SYSTEM_TIME messages,
6113
# so get_sim_time breaks:
6114
self.send_cmd_enter_cpu_lockup()
6115
start_time = time.time() # not sim time!
6116
self.context_push()
6117
self.context_collect("STATUSTEXT")
6118
while True:
6119
want = "Initialising ArduPilot"
6120
if time.time() - start_time > 30:
6121
raise NotAchievedException("Did not get %s" % want)
6122
# we still need to parse the incoming messages:
6123
try:
6124
self.wait_statustext(want, timeout=0.1, check_context=True, wallclock_timeout=1)
6125
break
6126
except AutoTestTimeoutException:
6127
pass
6128
self.context_pop()
6129
# Different scaling for RC input and servo output means the
6130
# servo output value isn't the rc input value:
6131
self.progress("Setting RC to 1200")
6132
self.rc_queue.put({2: 1200})
6133
self.progress("Waiting for servo of 1260")
6134
self.cpufailsafe_wait_servo_channel_value(2, 1260)
6135
self.rc_queue.put({2: 1700})
6136
self.cpufailsafe_wait_servo_channel_value(2, 1660)
6137
self.reset_SITL_commandline()
6138
6139
def mavproxy_arm_vehicle(self, mavproxy):
6140
"""Arm vehicle with mavlink arm message send from MAVProxy."""
6141
self.progress("Arm motors with MavProxy")
6142
mavproxy.send('arm throttle\n')
6143
self.wait_armed()
6144
self.progress("ARMED")
6145
return True
6146
6147
def mavproxy_disarm_vehicle(self, mavproxy):
6148
"""Disarm vehicle with mavlink disarm message send from MAVProxy."""
6149
self.progress("Disarm motors with MavProxy")
6150
mavproxy.send('disarm\n')
6151
self.wait_disarmed()
6152
6153
def arm_motors_with_rc_input(self, timeout=20):
6154
"""Arm motors with radio."""
6155
self.progress("Arm motors with radio")
6156
self.set_output_to_max(self.get_stick_arming_channel())
6157
tstart = self.get_sim_time()
6158
while True:
6159
self.wait_heartbeat()
6160
tdelta = self.get_sim_time_cached() - tstart
6161
if self.mav.motors_armed():
6162
self.progress("MOTORS ARMED OK WITH RADIO")
6163
self.set_output_to_trim(self.get_stick_arming_channel())
6164
self.progress("Arm in %ss" % tdelta) # TODO check arming time
6165
return
6166
self.progress("Not armed after %f seconds" % (tdelta))
6167
if tdelta > timeout:
6168
break
6169
self.set_output_to_trim(self.get_stick_arming_channel())
6170
raise NotAchievedException("Failed to ARM with radio")
6171
6172
def disarm_motors_with_rc_input(self, timeout=20, watch_for_disabled=False):
6173
"""Disarm motors with radio."""
6174
self.progress("Disarm motors with radio")
6175
self.do_timesync_roundtrip()
6176
self.context_push()
6177
self.context_collect('STATUSTEXT')
6178
self.set_output_to_min(self.get_stick_arming_channel())
6179
tstart = self.get_sim_time()
6180
ret = False
6181
while self.get_sim_time_cached() < tstart + timeout:
6182
self.wait_heartbeat()
6183
if not self.mav.motors_armed():
6184
disarm_delay = self.get_sim_time_cached() - tstart
6185
self.progress("MOTORS DISARMED OK WITH RADIO (in %ss)" % disarm_delay)
6186
ret = True
6187
break
6188
if self.statustext_in_collections("Rudder disarm: disabled"):
6189
self.progress("Found 'Rudder disarm: disabled' in statustext")
6190
break
6191
self.context_clear_collection('STATUSTEXT')
6192
self.set_output_to_trim(self.get_stick_arming_channel())
6193
self.context_pop()
6194
if not ret:
6195
raise NotAchievedException("Failed to DISARM with RC input")
6196
6197
def arm_motors_with_switch(self, switch_chan, timeout=20):
6198
"""Arm motors with switch."""
6199
self.progress("Arm motors with switch %d" % switch_chan)
6200
self.set_rc(switch_chan, 2000)
6201
tstart = self.get_sim_time()
6202
while self.get_sim_time_cached() - tstart < timeout:
6203
self.wait_heartbeat()
6204
if self.mav.motors_armed():
6205
self.progress("MOTORS ARMED OK WITH SWITCH")
6206
return
6207
raise NotAchievedException("Failed to ARM with switch")
6208
6209
def disarm_motors_with_switch(self, switch_chan, timeout=20):
6210
"""Disarm motors with switch."""
6211
self.progress("Disarm motors with switch %d" % switch_chan)
6212
self.set_rc(switch_chan, 1000)
6213
tstart = self.get_sim_time()
6214
while self.get_sim_time_cached() < tstart + timeout:
6215
self.wait_heartbeat()
6216
if not self.mav.motors_armed():
6217
self.progress("MOTORS DISARMED OK WITH SWITCH")
6218
return
6219
raise NotAchievedException("Failed to DISARM with switch")
6220
6221
def disarm_wait(self, timeout=10):
6222
tstart = self.get_sim_time()
6223
while True:
6224
if self.get_sim_time_cached() - tstart > timeout:
6225
raise NotAchievedException("Did not disarm")
6226
self.wait_heartbeat()
6227
if not self.mav.motors_armed():
6228
return
6229
6230
def wait_autodisarm_motors(self):
6231
"""Wait for Autodisarm motors within disarm delay
6232
this feature is only available in copter (DISARM_DELAY) and plane (LAND_DISARMDELAY)."""
6233
self.progress("Wait autodisarming motors")
6234
disarm_delay = self.get_disarm_delay()
6235
tstart = self.get_sim_time()
6236
timeout = disarm_delay * 2
6237
while self.get_sim_time_cached() < tstart + timeout:
6238
self.wait_heartbeat()
6239
if not self.mav.motors_armed():
6240
disarm_time = self.get_sim_time_cached() - tstart
6241
self.progress("MOTORS AUTODISARMED")
6242
self.progress("Autodisarm in %ss, expect less than %ss" % (disarm_time, disarm_delay))
6243
return disarm_time <= disarm_delay
6244
raise AutoTestTimeoutException("Failed to AUTODISARM")
6245
6246
def set_autodisarm_delay(self, delay):
6247
"""Set autodisarm delay"""
6248
raise ErrorException("Auto disarm is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
6249
6250
@staticmethod
6251
def should_fetch_all_for_parameter_change(param_name):
6252
return False # FIXME: if we allow MAVProxy then allow this
6253
if fnmatch.fnmatch(param_name, "*_ENABLE") or fnmatch.fnmatch(param_name, "*_ENABLED"):
6254
return True
6255
if param_name in ["ARSPD_TYPE",
6256
"ARSPD2_TYPE",
6257
"BATT2_MONITOR",
6258
"CAN_DRIVER",
6259
"COMPASS_PMOT_EN",
6260
"OSD_TYPE",
6261
"RSSI_TYPE",
6262
"WENC_TYPE"]:
6263
return True
6264
return False
6265
6266
def set_parameter_bit(self, name: str, bit_offset: int) -> None:
6267
'''set bit in parameter to true, preserving values of other bits'''
6268
value = int(self.get_parameter(name))
6269
value |= 1 << bit_offset
6270
self.set_parameter(name, value)
6271
6272
def clear_parameter_bit(self, name: str, bit_offset: int) -> None:
6273
'''set bit in parameter to true, preserving values of other bits'''
6274
value = int(self.get_parameter(name))
6275
value &= ~(1 << bit_offset)
6276
self.set_parameter(name, value)
6277
6278
def send_set_parameter_direct(self, name, value):
6279
self.mav.mav.param_set_send(self.sysid_thismav(),
6280
1,
6281
name.encode('ascii'),
6282
value,
6283
mavutil.mavlink.MAV_PARAM_TYPE_REAL32)
6284
6285
def send_set_parameter_mavproxy(self, name, value):
6286
self.mavproxy.send("param set %s %s\n" % (name, str(value)))
6287
6288
def send_set_parameter(self, name, value, verbose=False):
6289
if verbose:
6290
self.progress("Send set param for (%s) (%f)" % (name, value))
6291
return self.send_set_parameter_direct(name, value)
6292
6293
def set_parameter(self, name, value, **kwargs):
6294
self.set_parameters({name: value}, **kwargs)
6295
6296
def set_parameters(self, parameters, add_to_context=True, epsilon_pct=0.00001, verbose=True, attempts=None):
6297
"""Set parameters from vehicle."""
6298
6299
want = copy.copy(parameters)
6300
self.progress("set_parameters: (%s)" % str(want))
6301
self.drain_mav()
6302
if len(want) == 0:
6303
return
6304
6305
if attempts is None:
6306
# we can easily fill ArduPilot's param-set/param-get queue
6307
# which is quite short. So we retry *a lot*.
6308
attempts = len(want) * 10
6309
6310
param_value_messages = []
6311
6312
def add_param_value(mav, m):
6313
t = m.get_type()
6314
if t != "PARAM_VALUE":
6315
return
6316
param_value_messages.append(m)
6317
6318
self.install_message_hook(add_param_value)
6319
6320
original_values = {}
6321
autopilot_values = {}
6322
for i in range(attempts):
6323
self.drain_mav(quiet=True)
6324
self.drain_all_pexpects()
6325
received = set()
6326
for (name, value) in want.items():
6327
if verbose:
6328
self.progress("%s want=%f autopilot=%s (attempt=%u/%u)" %
6329
(name, value, autopilot_values.get(name, 'None'), i+1, attempts))
6330
if name not in autopilot_values:
6331
if verbose:
6332
self.progress("Requesting (%s)" % (name,))
6333
self.send_get_parameter_direct(name)
6334
continue
6335
delta = abs(autopilot_values[name] - value)
6336
if delta <= epsilon_pct*0.01*abs(value):
6337
# correct value
6338
self.progress("%s is now %f" % (name, autopilot_values[name]))
6339
if add_to_context:
6340
context_param_name_list = [p[0] for p in self.context_get().parameters]
6341
if name.upper() not in context_param_name_list:
6342
self.context_get().parameters.append((name, original_values[name]))
6343
received.add(name)
6344
continue
6345
self.progress("Sending set (%s) to (%f) (old=%f)" % (name, value, original_values[name]))
6346
self.send_set_parameter_direct(name, value)
6347
for name in received:
6348
del want[name]
6349
if len(want):
6350
# problem here is that a reboot can happen after we
6351
# send the request but before we receive the reply:
6352
try:
6353
self.do_timesync_roundtrip(quiet=True)
6354
except AutoTestTimeoutException:
6355
pass
6356
for m in param_value_messages:
6357
if m.param_id in want:
6358
self.progress("Received wanted PARAM_VALUE %s=%f" %
6359
(str(m.param_id), m.param_value))
6360
autopilot_values[m.param_id] = m.param_value
6361
if m.param_id not in original_values:
6362
original_values[m.param_id] = m.param_value
6363
param_value_messages = []
6364
6365
self.remove_message_hook(add_param_value)
6366
6367
if len(want) == 0:
6368
return
6369
raise ValueError("Failed to set parameters (%s)" % want)
6370
6371
def reorder_compass_appearance(self, device_ids):
6372
"""
6373
Set compass appearance order by mapping device IDs to SIM_MAGx_DEVID parameters.
6374
6375
Args:
6376
device_ids: List of device IDs in desired order
6377
6378
Example:
6379
# Swap compass 2 and compass 4
6380
original_ids = self.get_sim_mag_devids(6)
6381
# Reorder: [dev1, dev4, dev3, dev2, dev5, dev6]
6382
reordered = [original_ids[0], original_ids[3], original_ids[2],
6383
original_ids[1], original_ids[4], original_ids[5]]
6384
self.reorder_compass_appearance(reordered)
6385
"""
6386
# Build parameter dictionary
6387
params = {}
6388
for i, dev_id in enumerate(device_ids):
6389
param_name = f"SIM_MAG{i + 1}_DEVID"
6390
params[param_name] = dev_id
6391
6392
# Apply the parameters
6393
self.set_parameters(params)
6394
6395
def check_mag_devids_detected(self, num_compasses):
6396
"""
6397
Check if all SIM_MAGx_DEVID values are present in COMPASS_DEV_ID parameters.
6398
6399
Args:
6400
num_compasses: Number of compasses to check
6401
6402
Raises:
6403
NotAchievedException: If any SIM_MAG device ID is not found in COMPASS_DEV_ID slots
6404
"""
6405
# Fetch SIM_MAGx_DEVID values
6406
sim_device_ids = self.get_sim_mag_devids(num_compasses)
6407
6408
# Fetch COMPASS_DEV_ID values
6409
compass_dev_ids = []
6410
for i in range(1, num_compasses + 1):
6411
suffix = "" if i == 1 else str(i)
6412
dev_id = self.get_parameter(f"COMPASS_DEV_ID{suffix}")
6413
self.progress(f"COMPASS_DEV_ID{suffix} = {dev_id}")
6414
compass_dev_ids.append(dev_id)
6415
6416
# Check that each SIM_MAG device ID is present in COMPASS_DEV_ID
6417
for sim_id in sim_device_ids:
6418
if sim_id not in compass_dev_ids:
6419
raise NotAchievedException(
6420
f"SIM_MAG device ID {sim_id} not found in COMPASS_DEV_ID slots. "
6421
f"SIM IDs: {sim_device_ids}, COMPASS IDs: {compass_dev_ids}"
6422
)
6423
6424
self.progress(f"All {num_compasses} compass device IDs detected")
6425
6426
def get_sim_mag_devids(self, num_compasses):
6427
"""
6428
Fetch list of device IDs from SIM_MAGx_DEVID parameters.
6429
6430
Args:
6431
num_compasses: Number of compasses to fetch
6432
6433
Returns:
6434
List of device IDs from SIM_MAG1_DEVID through SIM_MAGn_DEVID
6435
"""
6436
device_ids = []
6437
for i in range(1, num_compasses + 1):
6438
dev_id = self.get_parameter(f"SIM_MAG{i}_DEVID")
6439
device_ids.append(dev_id)
6440
self.progress(f"SIM_MAG{i}_DEVID = {dev_id}")
6441
return device_ids
6442
6443
# FIXME: modify assert_parameter_value to take epsilon_pct instead:
6444
def assert_parameter_value_pct(self, name, expected_value, max_error_percent):
6445
value = self.get_parameter_direct(name, verbose=False)
6446
6447
# Convert to ratio and find limits
6448
error_ratio = max_error_percent / 100
6449
limits = [expected_value * (1 + error_ratio), expected_value * (1 - error_ratio)]
6450
6451
# Ensure that min and max are always the correct way round
6452
upper_limit = max(limits)
6453
lower_limit = min(limits)
6454
6455
# Work out the true error percentage
6456
error_percent = math.nan
6457
if expected_value != 0:
6458
error_percent = abs(1.0 - (value / expected_value)) * 100
6459
6460
# Check value is within limits
6461
if (value > upper_limit) or (value < lower_limit):
6462
raise ValueError("%s expected %f +/- %f%% (%f to %f) got %s with %f%% error" % (
6463
name,
6464
expected_value,
6465
max_error_percent,
6466
lower_limit,
6467
upper_limit,
6468
value,
6469
error_percent))
6470
6471
self.progress("%s: (%f) check passed %f%% error less than %f%%" % (name, value, error_percent, max_error_percent))
6472
6473
def fetch_all_parameters(self):
6474
self.mav.mav.param_request_list_send(self.sysid_thismav(), 1)
6475
tstart = self.get_sim_time_cached()
6476
ret = {}
6477
param_count = 0
6478
while True:
6479
if param_count > 100 and len(ret) == param_count:
6480
break
6481
if self.get_sim_time_cached() - tstart > 5:
6482
raise NotAchievedException("Did not get all params")
6483
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)
6484
if m is None:
6485
continue
6486
if param_count is None or m.param_count > param_count:
6487
param_count = m.param_count
6488
ret[m.param_id] = m.param_value
6489
6490
return ret
6491
6492
def get_parameter(self, *args, **kwargs):
6493
return self.get_parameter_direct(*args, **kwargs)
6494
6495
def send_get_parameter_direct(self, name):
6496
encname = name
6497
if not isinstance(encname, bytes):
6498
encname = bytes(encname, 'ascii')
6499
self.mav.mav.param_request_read_send(self.sysid_thismav(),
6500
1,
6501
encname,
6502
-1)
6503
6504
def get_parameter_direct(self, name, attempts=1, timeout=60, verbose=True, timeout_in_wallclock=False):
6505
while attempts > 0:
6506
attempts -= 1
6507
if verbose:
6508
self.progress("Sending param_request_read for (%s)" % name)
6509
# we MUST parse here or collections fail where we need
6510
# them to work!
6511
self.drain_mav(quiet=True)
6512
if timeout_in_wallclock:
6513
tstart = time.time()
6514
else:
6515
tstart = self.get_sim_time()
6516
self.send_get_parameter_direct(name)
6517
while True:
6518
if timeout_in_wallclock:
6519
now = time.time()
6520
else:
6521
now = self.get_sim_time_cached()
6522
if tstart > now:
6523
self.progress("Time wrap detected")
6524
# we're going to have to send another request...
6525
break
6526
delta_time = now - tstart
6527
if delta_time > timeout:
6528
break
6529
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)
6530
if verbose:
6531
self.progress("get_parameter(%s): %s" % (name, str(m), ))
6532
if m is None:
6533
continue
6534
if m.param_id == name:
6535
if delta_time > 5:
6536
self.progress("Long time to get parameter: %fs" % (delta_time,))
6537
return m.param_value
6538
if verbose:
6539
self.progress("(%s) != (%s)" % (m.param_id, name,))
6540
raise NotAchievedException("Failed to retrieve parameter (%s)" % name)
6541
6542
def get_parameter_mavproxy(self, mavproxy, name, attempts=1, timeout=60):
6543
"""Get parameters from vehicle."""
6544
for i in range(0, attempts):
6545
mavproxy.send("param fetch %s\n" % name)
6546
try:
6547
mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/attempts)
6548
try:
6549
# sometimes race conditions garble the MAVProxy output
6550
ret = float(mavproxy.match.group(1))
6551
except ValueError:
6552
continue
6553
return ret
6554
except pexpect.TIMEOUT:
6555
pass
6556
raise NotAchievedException("Failed to retrieve parameter (%s)" % name)
6557
6558
def get_parameters(self, some_list, **kwargs):
6559
ret = {}
6560
6561
for n in some_list:
6562
ret[n] = self.get_parameter(n, **kwargs)
6563
6564
return ret
6565
6566
def context_get(self):
6567
"""Get Saved parameters."""
6568
return self.contexts[-1]
6569
6570
def context_push(self):
6571
"""Save a copy of the parameters."""
6572
context = Context()
6573
self.contexts.append(context)
6574
# add a message hook so we can collect messages conveniently:
6575
6576
def mh(mav, m):
6577
t = m.get_type()
6578
if t in context.collections:
6579
context.collections[t].append(m)
6580
self.install_message_hook_context(mh)
6581
6582
def context_collect(self, msg_type):
6583
'''start collecting messages of type msg_type into context collection'''
6584
context = self.context_get()
6585
if msg_type in context.collections:
6586
return
6587
context.collections[msg_type] = []
6588
6589
def context_collection(self, msg_type):
6590
'''return messages in collection'''
6591
context = self.context_get()
6592
if msg_type not in context.collections:
6593
raise NotAchievedException("Not collecting (%s)" % str(msg_type))
6594
return context.collections[msg_type]
6595
6596
def context_clear_collection(self, msg_type):
6597
'''clear collection of message type msg_type'''
6598
context = self.context_get()
6599
if msg_type not in context.collections:
6600
raise NotAchievedException("Not collecting (%s)" % str(msg_type))
6601
context.collections[msg_type] = []
6602
6603
def context_stop_collecting(self, msg_type):
6604
'''stop collecting messages of type msg_type in context collection. Returns the collected messages'''
6605
context = self.context_get()
6606
if msg_type not in context.collections:
6607
raise Exception("Not collecting %s" % str(msg_type))
6608
ret = context.collections[msg_type]
6609
del context.collections[msg_type]
6610
return ret
6611
6612
def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False):
6613
"""Set parameters to origin values in reverse order."""
6614
dead = self.contexts.pop()
6615
# remove hooks first; these hooks can raise exceptions which
6616
# we really don't want...
6617
if not hooks_already_removed:
6618
for hook in dead.message_hooks:
6619
self.remove_message_hook(hook)
6620
for script in dead.installed_scripts:
6621
self.remove_installed_script(script)
6622
for (message_id, rate_hz) in dead.overridden_message_rates.items():
6623
self.set_message_rate_hz(message_id, rate_hz)
6624
for module in dead.installed_modules:
6625
print("Removing module (%s)" % module)
6626
self.remove_installed_modules(module)
6627
if dead.sitl_commandline_customised and len(self.contexts):
6628
self.contexts[-1].sitl_commandline_customised = True
6629
if dead.raising_debug_trap_on_exceptions:
6630
sys.settrace(None)
6631
6632
dead_parameters_dict = {}
6633
for p in dead.parameters:
6634
dead_parameters_dict[p[0]] = p[1]
6635
if process_interaction_allowed:
6636
self.set_parameters(dead_parameters_dict, add_to_context=False)
6637
6638
if getattr(self, "old_binary", None) is not None:
6639
self.stop_SITL()
6640
with open(self.binary, "wb") as f:
6641
f.write(self.old_binary)
6642
f.close()
6643
self.start_SITL(wipe=False)
6644
self.set_streamrate(self.sitl_streamrate())
6645
elif dead.reboot_sitl_was_done:
6646
self.progress("Doing implicit context-pop reboot")
6647
self.reboot_sitl(mark_context=False)
6648
6649
# the following method is broken under Python2; can't **build_opts
6650
# def context_start_custom_binary(self, extra_defines={}):
6651
# # grab copy of current binary:
6652
# context = self.context_get()
6653
# if getattr(context, "old_binary", None) is not None:
6654
# raise ValueError("Not nestable at the moment")
6655
# with open(self.binary, "rb") as f:
6656
# self.old_binary = f.read()
6657
# f.close()
6658
# build_opts = copy.copy(self.build_opts)
6659
# build_opts["extra_defines"] = extra_defines
6660
# util.build_SITL(
6661
# 'bin/arducopter', # FIXME!
6662
# **build_opts,
6663
# )
6664
# self.stop_SITL()
6665
# self.start_SITL(wipe=False)
6666
# self.set_streamrate(self.sitl_streamrate())
6667
6668
class Context(object):
6669
def __init__(self, testsuite):
6670
self.testsuite = testsuite
6671
6672
def __enter__(self):
6673
self.testsuite.context_push()
6674
6675
def __exit__(self, type, value, traceback):
6676
self.testsuite.context_pop()
6677
return False # re-raise any exception
6678
6679
def sysid_thismav(self):
6680
return 1
6681
6682
def create_MISSION_ITEM_INT(
6683
self,
6684
t,
6685
p1=0,
6686
p2=0,
6687
p3=0,
6688
p4=0,
6689
x=0,
6690
y=0,
6691
z=0,
6692
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
6693
autocontinue=0,
6694
current=0,
6695
target_system=1,
6696
target_component=1,
6697
seq=0,
6698
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
6699
):
6700
return self.mav.mav.mission_item_int_encode(
6701
target_system,
6702
target_component,
6703
seq, # seq
6704
frame,
6705
t,
6706
current, # current
6707
autocontinue, # autocontinue
6708
p1, # p1
6709
p2, # p2
6710
p3, # p3
6711
p4, # p4
6712
x, # latitude
6713
y, # longitude
6714
z, # altitude
6715
mission_type
6716
)
6717
6718
def run_cmd_int(self,
6719
command,
6720
p1=0,
6721
p2=0,
6722
p3=0,
6723
p4=0,
6724
x=0,
6725
y=0,
6726
z=0,
6727
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
6728
timeout=10,
6729
target_sysid=None,
6730
target_compid=None,
6731
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
6732
p5=None,
6733
p6=None,
6734
p7=None,
6735
quiet=False,
6736
mav=None,
6737
):
6738
6739
if mav is None:
6740
mav = self.mav
6741
6742
if p5 is not None:
6743
x = p5
6744
if p6 is not None:
6745
y = p6
6746
if p7 is not None:
6747
z = p7
6748
6749
if target_sysid is None:
6750
target_sysid = self.sysid_thismav()
6751
if target_compid is None:
6752
target_compid = 1
6753
6754
self.get_sim_time() # required for timeout in run_cmd_get_ack to work
6755
6756
"""Send a MAVLink command int."""
6757
if not quiet:
6758
try:
6759
command_name = mavutil.mavlink.enums["MAV_CMD"][command].name
6760
except KeyError:
6761
command_name = "UNKNOWNu"
6762
self.progress("Sending COMMAND_INT to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%u p6=%u p7=%f f=%u)" % (
6763
target_sysid,
6764
target_compid,
6765
command_name,
6766
command,
6767
p1,
6768
p2,
6769
p3,
6770
p4,
6771
x,
6772
y,
6773
z,
6774
frame
6775
))
6776
mav.mav.command_int_send(target_sysid,
6777
target_compid,
6778
frame,
6779
command,
6780
0, # current
6781
0, # autocontinue
6782
p1,
6783
p2,
6784
p3,
6785
p4,
6786
x,
6787
y,
6788
z)
6789
self.run_cmd_get_ack(command, want_result, timeout, mav=mav)
6790
6791
def send_cmd(self,
6792
command,
6793
p1=0,
6794
p2=0,
6795
p3=0,
6796
p4=0,
6797
p5=0,
6798
p6=0,
6799
p7=0,
6800
target_sysid=None,
6801
target_compid=None,
6802
mav=None,
6803
quiet=False,
6804
):
6805
"""Send a MAVLink command long."""
6806
if mav is None:
6807
mav = self.mav
6808
if target_sysid is None:
6809
target_sysid = self.sysid_thismav()
6810
if target_compid is None:
6811
target_compid = 1
6812
if not quiet:
6813
try:
6814
command_name = mavutil.mavlink.enums["MAV_CMD"][command].name
6815
except KeyError:
6816
command_name = "UNKNOWN"
6817
self.progress("Sending COMMAND_LONG to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" %
6818
(
6819
target_sysid,
6820
target_compid,
6821
command_name,
6822
command,
6823
p1,
6824
p2,
6825
p3,
6826
p4,
6827
p5,
6828
p6,
6829
p7))
6830
mav.mav.command_long_send(target_sysid,
6831
target_compid,
6832
command,
6833
1, # confirmation
6834
p1,
6835
p2,
6836
p3,
6837
p4,
6838
p5,
6839
p6,
6840
p7)
6841
6842
def run_cmd(self,
6843
command,
6844
p1=0,
6845
p2=0,
6846
p3=0,
6847
p4=0,
6848
p5=0,
6849
p6=0,
6850
p7=0,
6851
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
6852
target_sysid=None,
6853
target_compid=None,
6854
timeout=10,
6855
quiet=False,
6856
mav=None):
6857
self.drain_mav(mav=mav)
6858
self.get_sim_time() # required for timeout in run_cmd_get_ack to work
6859
self.send_cmd(
6860
command,
6861
p1,
6862
p2,
6863
p3,
6864
p4,
6865
p5,
6866
p6,
6867
p7,
6868
target_sysid=target_sysid,
6869
target_compid=target_compid,
6870
mav=mav,
6871
quiet=quiet,
6872
)
6873
self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet, mav=mav)
6874
6875
def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, ignore_in_progress=None):
6876
# note that the caller should ensure that this cached
6877
# timestamp is reasonably up-to-date!
6878
if mav is None:
6879
mav = self.mav
6880
if ignore_in_progress is None:
6881
ignore_in_progress = want_result != mavutil.mavlink.MAV_RESULT_IN_PROGRESS
6882
tstart = self.get_sim_time_cached()
6883
while True:
6884
if mav != self.mav:
6885
self.drain_mav()
6886
delta_time = self.get_sim_time_cached() - tstart
6887
if delta_time > timeout:
6888
raise AutoTestTimeoutException("Did not get good COMMAND_ACK within %fs" % timeout)
6889
m = mav.recv_match(type='COMMAND_ACK',
6890
blocking=True,
6891
timeout=0.1)
6892
if m is None:
6893
continue
6894
if not quiet:
6895
self.progress("ACK received: %s (%fs)" % (str(m), delta_time))
6896
if m.command == command:
6897
if m.result == mavutil.mavlink.MAV_RESULT_IN_PROGRESS and ignore_in_progress:
6898
continue
6899
if m.result != want_result:
6900
raise ValueError("Expected %s got %s" % (
6901
mavutil.mavlink.enums["MAV_RESULT"][want_result].name,
6902
mavutil.mavlink.enums["MAV_RESULT"][m.result].name))
6903
break
6904
6905
def set_current_waypoint_using_mav_cmd_do_set_mission_current(
6906
self,
6907
seq,
6908
reset=0,
6909
target_sysid=1,
6910
target_compid=1):
6911
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
6912
p1=seq,
6913
p2=reset,
6914
timeout=1,
6915
target_sysid=target_sysid,
6916
target_compid=target_compid)
6917
6918
def set_current_waypoint_using_mission_set_current(
6919
self,
6920
seq,
6921
target_sysid=1,
6922
target_compid=1,
6923
check_afterwards=True):
6924
self.mav.mav.mission_set_current_send(target_sysid,
6925
target_compid,
6926
seq)
6927
if check_afterwards:
6928
self.wait_current_waypoint(seq, timeout=10)
6929
6930
def set_current_waypoint(self, seq, target_sysid=1, target_compid=1, check_afterwards=True):
6931
return self.set_current_waypoint_using_mission_set_current(
6932
seq,
6933
target_sysid,
6934
target_compid,
6935
check_afterwards=check_afterwards
6936
)
6937
6938
def verify_parameter_values(self, parameter_stuff, max_delta=0.0):
6939
bad = ""
6940
for param in parameter_stuff:
6941
fetched_value = self.get_parameter(param)
6942
wanted_value = parameter_stuff[param]
6943
if isinstance(wanted_value, tuple):
6944
max_delta = wanted_value[1]
6945
wanted_value = wanted_value[0]
6946
if abs(fetched_value - wanted_value) > max_delta:
6947
bad += "%s=%f (want=%f +/-%f) " % (param, fetched_value, wanted_value, max_delta)
6948
if len(bad):
6949
raise NotAchievedException("Bad parameter values: %s" %
6950
(bad,))
6951
6952
#################################################
6953
# UTILITIES
6954
#################################################
6955
def lineno(self):
6956
'''return line number'''
6957
frameinfo = getframeinfo(currentframe().f_back)
6958
# print(frameinfo.filename, frameinfo.lineno)
6959
return frameinfo.lineno
6960
6961
@staticmethod
6962
def longitude_scale(lat):
6963
ret = math.cos(lat * (math.radians(1)))
6964
print("scale=%f" % ret)
6965
return ret
6966
6967
@staticmethod
6968
def get_distance(loc1, loc2):
6969
"""Get ground distance between two locations."""
6970
return TestSuite.get_distance_accurate(loc1, loc2)
6971
# dlat = loc2.lat - loc1.lat
6972
# try:
6973
# dlong = loc2.lng - loc1.lng
6974
# except AttributeError:
6975
# dlong = loc2.lon - loc1.lon
6976
6977
# return math.sqrt((dlat*dlat) + (dlong*dlong)*TestSuite.longitude_scale(loc2.lat)) * 1.113195e5
6978
6979
@staticmethod
6980
def get_distance_accurate(loc1, loc2):
6981
"""Get ground distance between two locations."""
6982
try:
6983
lon1 = loc1.lng
6984
lon2 = loc2.lng
6985
except AttributeError:
6986
lon1 = loc1.lon
6987
lon2 = loc2.lon
6988
6989
return mp_util.gps_distance(loc1.lat, lon1, loc2.lat, lon2)
6990
6991
def assert_distance(self, loc1, loc2, min_distance, max_distance):
6992
dist = self.get_distance_accurate(loc1, loc2)
6993
if dist < min_distance or dist > max_distance:
6994
raise NotAchievedException("Expected distance %f to be between %f and %f" %
6995
(dist, min_distance, max_distance))
6996
self.progress("Distance %f is between %f and %f" %
6997
(dist, min_distance, max_distance))
6998
6999
@staticmethod
7000
def get_latlon_attr(loc, attrs):
7001
'''return any found latitude attribute from loc'''
7002
ret = None
7003
for attr in attrs:
7004
if hasattr(loc, attr):
7005
ret = getattr(loc, attr)
7006
break
7007
if ret is None:
7008
raise ValueError("None of %s in loc(%s)" % (str(attrs), str(loc)))
7009
return ret
7010
7011
@staticmethod
7012
def get_lat_attr(loc):
7013
'''return any found latitude attribute from loc'''
7014
return TestSuite.get_latlon_attr(loc, ["lat", "latitude"])
7015
7016
@staticmethod
7017
def get_lon_attr(loc):
7018
'''return any found latitude attribute from loc'''
7019
return TestSuite.get_latlon_attr(loc, ["lng", "lon", "longitude"])
7020
7021
@staticmethod
7022
def get_distance_int(loc1, loc2):
7023
"""Get ground distance between two locations in the normal "int" form
7024
- lat/lon multiplied by 1e7"""
7025
loc1_lat = TestSuite.get_lat_attr(loc1)
7026
loc2_lat = TestSuite.get_lat_attr(loc2)
7027
loc1_lon = TestSuite.get_lon_attr(loc1)
7028
loc2_lon = TestSuite.get_lon_attr(loc2)
7029
7030
return TestSuite.get_distance_accurate(
7031
mavutil.location(loc1_lat*1e-7, loc1_lon*1e-7),
7032
mavutil.location(loc2_lat*1e-7, loc2_lon*1e-7))
7033
7034
# dlat = loc2_lat - loc1_lat
7035
# dlong = loc2_lon - loc1_lon
7036
#
7037
# dlat /= 10000000.0
7038
# dlong /= 10000000.0
7039
#
7040
# return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e5
7041
7042
def bearing_to(self, loc):
7043
'''return bearing from here to location'''
7044
here = self.mav.location()
7045
return self.get_bearing(here, loc)
7046
7047
@staticmethod
7048
def get_bearing(loc1, loc2):
7049
"""Get bearing from loc1 to loc2."""
7050
off_x = loc2.lng - loc1.lng
7051
off_y = loc2.lat - loc1.lat
7052
bearing = 90.00 + math.atan2(-off_y, off_x) * 57.2957795
7053
if bearing < 0:
7054
bearing += 360.00
7055
return bearing
7056
7057
def send_cmd_do_set_mode(self, mode):
7058
self.send_cmd(
7059
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
7060
p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
7061
p2=self.get_mode_from_mode_mapping(mode),
7062
)
7063
7064
def assert_mode(self, mode):
7065
self.wait_mode(mode, timeout=0)
7066
7067
def change_mode(self, mode, timeout=60):
7068
'''change vehicle flightmode'''
7069
self.wait_heartbeat()
7070
self.progress("Changing mode to %s" % mode)
7071
self.send_cmd_do_set_mode(mode)
7072
tstart = self.get_sim_time()
7073
while not self.mode_is(mode):
7074
custom_num = self.mav.messages['HEARTBEAT'].custom_mode
7075
self.progress("mav.flightmode=%s Want=%s custom=%u" % (
7076
self.mav.flightmode, mode, custom_num))
7077
if (timeout is not None and
7078
self.get_sim_time_cached() > tstart + timeout):
7079
raise WaitModeTimeout("Did not change mode")
7080
self.send_cmd_do_set_mode(mode)
7081
self.progress("Got mode %s" % mode)
7082
7083
def capable(self, capability):
7084
return self.get_autopilot_capabilities() & capability
7085
7086
def assert_capability(self, capability):
7087
if not self.capable(capability):
7088
name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name
7089
raise NotAchievedException("AutoPilot does not have capbility %s" % (name,))
7090
7091
def assert_no_capability(self, capability):
7092
if self.capable(capability):
7093
name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name
7094
raise NotAchievedException("AutoPilot has feature %s (when it shouldn't)" % (name,))
7095
7096
def get_autopilot_capabilities(self):
7097
self.context_push()
7098
self.context_collect('AUTOPILOT_VERSION')
7099
self.run_cmd(
7100
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
7101
p1=1, # 1: Request autopilot version
7102
)
7103
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10, check_context=True)
7104
self.context_pop()
7105
return m.capabilities
7106
7107
def decode_flight_sw_version(self, flight_sw_version: int):
7108
""" Decode 32 bit flight_sw_version mavlink parameter
7109
corresponds to encoding in ardupilot GCS_MAVLINK::send_autopilot_version."""
7110
fw_type_id = (flight_sw_version >> 0) % 256
7111
patch = (flight_sw_version >> 8) % 256
7112
minor = (flight_sw_version >> 16) % 256
7113
major = (flight_sw_version >> 24) % 256
7114
if fw_type_id == 0:
7115
fw_type = "dev"
7116
elif fw_type_id == 64:
7117
fw_type = "alpha"
7118
elif fw_type_id == 128:
7119
fw_type = "beta"
7120
elif fw_type_id == 192:
7121
fw_type = "rc"
7122
elif fw_type_id == 255:
7123
fw_type = "official"
7124
else:
7125
fw_type = "undefined"
7126
return major, minor, patch, fw_type
7127
7128
def get_autopilot_firmware_version(self):
7129
self.mav.mav.command_long_send(self.sysid_thismav(),
7130
1,
7131
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
7132
0, # confirmation
7133
1, # 1: Request autopilot version
7134
0,
7135
0,
7136
0,
7137
0,
7138
0,
7139
0)
7140
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)
7141
self.fcu_firmware_version = self.decode_flight_sw_version(m.flight_sw_version)
7142
7143
def hex_values_to_int(hex_values):
7144
# Convert ascii codes to characters
7145
hex_chars = [chr(int(hex_value)) for hex_value in hex_values]
7146
# Convert hex characters to integers, handle \x00 case
7147
int_values = [0 if hex_char == '\x00' else int(hex_char, 16) for hex_char in hex_chars]
7148
return int_values
7149
7150
fcu_hash_to_hex = ""
7151
for i in hex_values_to_int(m.flight_custom_version):
7152
fcu_hash_to_hex += f"{i:x}"
7153
self.fcu_firmware_hash = fcu_hash_to_hex
7154
self.progress(f"Firmware Version {self.fcu_firmware_version}")
7155
self.progress(f"Firmware hash {self.fcu_firmware_hash}")
7156
self.githash = util.get_git_hash(short=True)
7157
self.progress(f"Git hash {self.githash}")
7158
7159
def GetCapabilities(self):
7160
'''Get Capabilities'''
7161
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT)
7162
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION)
7163
7164
def get_mode_from_mode_mapping(self, mode) -> int:
7165
"""Validate and return the mode number from a string or int."""
7166
if isinstance(mode, int):
7167
return mode
7168
mode_map = self.mav.mode_mapping()
7169
if mode_map is None:
7170
mav_type = self.mav.messages['HEARTBEAT'].type
7171
mav_autopilot = self.mav.messages['HEARTBEAT'].autopilot
7172
raise ErrorException("No mode map for (mav_type=%s mav_autopilot=%s)" % (mav_type, mav_autopilot))
7173
if isinstance(mode, str):
7174
if mode in mode_map:
7175
return mode_map.get(mode)
7176
if mode in mode_map.values():
7177
return mode
7178
self.progress("No mode (%s); available modes '%s'" % (mode, mode_map))
7179
raise ErrorException("Unknown mode '%s'" % mode)
7180
7181
def get_mode_string_for_mode(self, mode):
7182
if isinstance(mode, str):
7183
return mode
7184
mode_map = self.mav.mode_mapping()
7185
if mode_map is None:
7186
return f"mode={mode}"
7187
for (n, v) in mode_map.items():
7188
if v == mode:
7189
return n
7190
self.progress(f"No mode ({mode} {type(mode)}); available modes '{mode_map}'")
7191
raise ErrorException("Unknown mode '%s'" % mode)
7192
7193
def run_cmd_do_set_mode(self,
7194
mode,
7195
timeout=30,
7196
run_cmd=None,
7197
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7198
if run_cmd is None:
7199
run_cmd = self.run_cmd
7200
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
7201
custom_mode = self.get_mode_from_mode_mapping(mode)
7202
run_cmd(
7203
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
7204
p1=base_mode,
7205
p2=custom_mode,
7206
want_result=want_result,
7207
timeout=timeout,
7208
)
7209
7210
def do_set_mode_via_command_XYZZY(self, mode, run_cmd, timeout=30):
7211
"""Set mode with a command long message."""
7212
tstart = self.get_sim_time()
7213
want_custom_mode = self.get_mode_from_mode_mapping(mode)
7214
while True:
7215
remaining = timeout - (self.get_sim_time_cached() - tstart)
7216
if remaining <= 0:
7217
raise AutoTestTimeoutException("Failed to change mode")
7218
self.run_cmd_do_set_mode(mode, run_cmd=run_cmd, timeout=10)
7219
m = self.wait_heartbeat()
7220
self.progress("Got mode=%u want=%u" % (m.custom_mode, want_custom_mode))
7221
if m.custom_mode == want_custom_mode:
7222
return
7223
7224
def do_set_mode_via_command_long(self, mode, timeout=30):
7225
self.do_set_mode_via_command_XYZZY(mode, self.run_cmd, timeout=timeout)
7226
7227
def do_set_mode_via_command_int(self, mode, timeout=30):
7228
self.do_set_mode_via_command_XYZZY(mode, self.run_cmd_int, timeout=timeout)
7229
7230
def mavproxy_do_set_mode_via_command_long(self, mavproxy, mode, timeout=30):
7231
"""Set mode with a command long message with Mavproxy."""
7232
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
7233
custom_mode = self.get_mode_from_mode_mapping(mode)
7234
tstart = self.get_sim_time()
7235
while True:
7236
remaining = timeout - (self.get_sim_time_cached() - tstart)
7237
if remaining <= 0:
7238
raise AutoTestTimeoutException("Failed to change mode")
7239
mavproxy.send("long DO_SET_MODE %u %u\n" %
7240
(base_mode, custom_mode))
7241
m = self.wait_heartbeat()
7242
if m.custom_mode == custom_mode:
7243
return True
7244
7245
def reach_heading_manual(self, heading, turn_right=True):
7246
"""Manually direct the vehicle to the target heading."""
7247
if self.is_copter() or self.is_sub():
7248
self.set_rc(4, 1580)
7249
self.wait_heading(heading)
7250
self.set_rc(4, 1500)
7251
if self.is_plane():
7252
self.set_rc(1, 1800)
7253
self.wait_heading(heading)
7254
self.set_rc(1, 1500)
7255
if self.is_rover():
7256
steering_pwm = 1700
7257
if not turn_right:
7258
steering_pwm = 1300
7259
self.set_rc(1, steering_pwm)
7260
self.set_rc(3, 1550)
7261
self.wait_heading(heading)
7262
self.set_rc(3, 1500)
7263
self.set_rc(1, 1500)
7264
7265
def assert_vehicle_location_is_at_startup_location(self, dist_max=1):
7266
here = self.mav.location()
7267
start_loc = self.sitl_start_location()
7268
dist = self.get_distance(here, start_loc)
7269
data = "dist=%f max=%f (here: %s start-loc: %s)" % (dist, dist_max, here, start_loc)
7270
7271
if dist > dist_max:
7272
raise NotAchievedException("Far from startup location: %s" % data)
7273
self.progress("Close to startup location: %s" % data)
7274
7275
def assert_simstate_location_is_at_startup_location(self, dist_max=1):
7276
simstate_loc = self.sim_location()
7277
start_loc = self.sitl_start_location()
7278
dist = self.get_distance(simstate_loc, start_loc)
7279
data = "dist=%f max=%f (simstate: %s start-loc: %s)" % (dist, dist_max, simstate_loc, start_loc)
7280
7281
if dist > dist_max:
7282
raise NotAchievedException("simstate far from startup location: %s" % data)
7283
self.progress("Simstate Close to startup location: %s" % data)
7284
7285
def reach_distance_manual(self, distance):
7286
"""Manually direct the vehicle to the target distance from home."""
7287
if self.is_copter():
7288
self.set_rc(2, 1350)
7289
self.wait_distance(distance, accuracy=5, timeout=60)
7290
self.set_rc(2, 1500)
7291
if self.is_plane():
7292
self.progress("NOT IMPLEMENTED")
7293
if self.is_rover():
7294
self.set_rc(3, 1700)
7295
self.wait_distance(distance, accuracy=2)
7296
self.set_rc(3, 1500)
7297
7298
def guided_achieve_heading(self, heading, accuracy=None):
7299
tstart = self.get_sim_time()
7300
self.run_cmd(
7301
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
7302
p1=heading, # target angle
7303
p2=10, # degrees/second
7304
p3=1, # -1 is counter-clockwise, 1 clockwise
7305
p4=0, # 1 for relative, 0 for absolute
7306
)
7307
while True:
7308
if self.get_sim_time_cached() - tstart > 200:
7309
raise NotAchievedException("Did not achieve heading")
7310
m = self.assert_receive_message('VFR_HUD')
7311
self.progress("heading=%d want=%d" % (m.heading, int(heading)))
7312
if accuracy is not None:
7313
delta = abs(m.heading - int(heading))
7314
if delta <= accuracy:
7315
return
7316
if m.heading == int(heading):
7317
return
7318
7319
def assert_heading(self, heading, accuracy=1):
7320
'''assert vehicle yaw is to heading (0-360)'''
7321
m = self.assert_receive_message('VFR_HUD')
7322
if self.heading_delta(heading, m.heading) > accuracy:
7323
raise NotAchievedException("Unexpected heading=%f want=%f" %
7324
(m.heading, heading))
7325
7326
def do_set_relay(self, relay_num, on_off, timeout=10):
7327
"""Set relay with a command long message."""
7328
self.progress("Set relay %d to %d" % (relay_num, on_off))
7329
self.run_cmd(
7330
mavutil.mavlink.MAV_CMD_DO_SET_RELAY,
7331
p1=relay_num,
7332
p2=on_off,
7333
timeout=timeout,
7334
)
7335
7336
def do_set_relay_mavproxy(self, relay_num, on_off):
7337
"""Set relay with mavproxy."""
7338
self.progress("Set relay %d to %d" % (relay_num, on_off))
7339
self.mavproxy.send('module load relay\n')
7340
self.mavproxy.expect("Loaded module relay")
7341
self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off))
7342
7343
def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7344
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result)
7345
7346
def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7347
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result)
7348
7349
def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7350
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result)
7351
7352
def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7353
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result)
7354
7355
#################################################
7356
# WAIT UTILITIES
7357
#################################################
7358
def delay_sim_time(self, seconds_to_wait, reason=None):
7359
"""Wait some second in SITL time."""
7360
tstart = self.get_sim_time()
7361
tnow = tstart
7362
r = "Delaying %f seconds"
7363
if reason is not None:
7364
r += " for %s" % reason
7365
self.progress(r % (seconds_to_wait,))
7366
while tstart + seconds_to_wait > tnow:
7367
tnow = self.get_sim_time(drain_mav=False)
7368
7369
def send_terrain_check_message(self):
7370
here = self.mav.location()
7371
self.mav.mav.terrain_check_send(int(here.lat * 1e7), int(here.lng * 1e7))
7372
7373
def get_terrain_height(self, verbose=False):
7374
self.send_terrain_check_message()
7375
m = self.assert_receive_message('TERRAIN_REPORT', very_verbose=True)
7376
return m.terrain_height
7377
7378
def get_altitude(self, relative=False, timeout=30, altitude_source=None):
7379
'''returns vehicles altitude in metres, possibly relative-to-home'''
7380
if altitude_source is None:
7381
if relative:
7382
altitude_source = "GLOBAL_POSITION_INT.relative_alt"
7383
else:
7384
altitude_source = "GLOBAL_POSITION_INT.alt"
7385
if altitude_source == "TERRAIN_REPORT.current_height":
7386
terrain = self.assert_receive_message('TERRAIN_REPORT')
7387
return terrain.current_height
7388
7389
(msg, field) = altitude_source.split('.')
7390
msg = self.poll_message(msg, quiet=True)
7391
divisor = 1000.0 # mm is pretty common in mavlink
7392
if altitude_source == "SIM_STATE.alt":
7393
divisor = 1.0
7394
return getattr(msg, field) / divisor
7395
7396
def assert_altitude(self, alt, accuracy=1, **kwargs):
7397
got_alt = self.get_altitude(**kwargs)
7398
if abs(alt - got_alt) > accuracy:
7399
raise NotAchievedException("Incorrect alt; want=%f got=%f" %
7400
(alt, got_alt))
7401
7402
def assert_rangefinder_distance_between(self, dist_min, dist_max):
7403
m = self.assert_receive_message('RANGEFINDER')
7404
7405
if m.distance < dist_min:
7406
raise NotAchievedException("below min height (%f < %f)" %
7407
(m.distance, dist_min))
7408
7409
if m.distance > dist_max:
7410
raise NotAchievedException("above max height (%f > %f)" %
7411
(m.distance, dist_max))
7412
7413
self.progress(f"Rangefinder distance {m.distance} is between {dist_min} and {dist_max}")
7414
7415
def assert_distance_sensor_quality(self, quality):
7416
m = self.assert_receive_message('DISTANCE_SENSOR')
7417
7418
if m.signal_quality != quality:
7419
raise NotAchievedException("Unexpected quality; want=%f got=%f" %
7420
(quality, m.signal_quality))
7421
7422
def get_rangefinder_distance(self):
7423
'''returns current rangefinder distance in metres'''
7424
m = self.assert_receive_message('DISTANCE_SENSOR', timeout=5)
7425
return m.current_distance * 0.01
7426
7427
def wait_rangefinder_distance(self, dist_min, dist_max, timeout=30, **kwargs):
7428
'''wait for DISTANCE_SENSOR distance in metres'''
7429
def validator(value2, target2=None):
7430
if dist_min <= value2 <= dist_max:
7431
return True
7432
else:
7433
return False
7434
7435
self.wait_and_maintain(
7436
value_name="RangeFinderDistance",
7437
target=dist_min,
7438
current_value_getter=lambda: self.get_rangefinder_distance(),
7439
accuracy=(dist_max - dist_min),
7440
validator=lambda value2, target2: validator(value2, target2),
7441
timeout=timeout,
7442
**kwargs
7443
)
7444
7445
def get_esc_rpm(self, esc):
7446
if esc > 4:
7447
raise ValueError("Only does 1-4")
7448
m = self.assert_receive_message('ESC_TELEMETRY_1_TO_4', verbose=True)
7449
return m.rpm[esc-1]
7450
7451
def find_first_set_bit(self, mask):
7452
'''returns offset of first-set-bit (counting from right) in mask. Returns None if no bits set'''
7453
pos = 0
7454
while mask != 0:
7455
if mask & 0x1:
7456
return pos
7457
mask = mask >> 1
7458
pos += 1
7459
return None
7460
7461
def get_rpm(self, rpm_sensor):
7462
m = self.assert_receive_message('RPM')
7463
if rpm_sensor == 1:
7464
ret = m.rpm1
7465
elif rpm_sensor == 2:
7466
ret = m.rpm2
7467
else:
7468
raise ValueError("Bad sensor id")
7469
if ret < 0.000001:
7470
# yay filtering!
7471
return 0
7472
return ret
7473
7474
def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs):
7475
'''wait for RPM to be between rpm_min and rpm_max'''
7476
def validator(value2, target2=None):
7477
return rpm_min <= value2 <= rpm_max
7478
self.wait_and_maintain(
7479
value_name="RPM%u" % rpm_sensor,
7480
target=(rpm_min+rpm_max)/2.0,
7481
current_value_getter=lambda: self.get_rpm(rpm_sensor),
7482
accuracy=rpm_max-rpm_min,
7483
validator=lambda value2, target2: validator(value2, target2),
7484
**kwargs
7485
)
7486
7487
def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):
7488
'''wait for ESC to be between rpm_min and rpm_max'''
7489
def validator(value2, target2=None):
7490
return rpm_min <= value2 <= rpm_max
7491
self.wait_and_maintain(
7492
value_name="ESC %u RPM" % esc,
7493
target=(rpm_min+rpm_max)/2.0,
7494
current_value_getter=lambda: self.get_esc_rpm(esc),
7495
accuracy=rpm_max-rpm_min,
7496
validator=lambda value2, target2: validator(value2, target2),
7497
**kwargs
7498
)
7499
7500
def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=None, **kwargs):
7501
"""Wait for a given altitude range."""
7502
assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude."
7503
7504
if timeout is None:
7505
timeout = 30
7506
7507
def validator(value2, target2=None):
7508
if altitude_min <= value2 <= altitude_max:
7509
return True
7510
else:
7511
return False
7512
7513
altitude_source = kwargs.get("altitude_source", None)
7514
7515
self.wait_and_maintain(
7516
value_name="Altitude",
7517
target=(altitude_min + altitude_max)*0.5,
7518
current_value_getter=lambda: self.get_altitude(
7519
relative=relative,
7520
timeout=timeout,
7521
altitude_source=altitude_source,
7522
),
7523
accuracy=(altitude_max - altitude_min)*0.5,
7524
validator=lambda value2, target2: validator(value2, target2),
7525
timeout=timeout,
7526
**kwargs
7527
)
7528
7529
def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True, altitude_source=None):
7530
"""Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration"""
7531
return self.wait_altitude(
7532
altitude_min=altitude_min,
7533
altitude_max=altitude_max,
7534
relative=relative,
7535
minimum_duration=minimum_duration,
7536
timeout=minimum_duration + 1,
7537
altitude_source=altitude_source,
7538
)
7539
7540
def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):
7541
"""Wait for a given vertical rate."""
7542
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
7543
7544
def get_climbrate(timeout2):
7545
msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)
7546
return msg.climb
7547
7548
def validator(value2, target2=None):
7549
if speed_min <= value2 <= speed_max:
7550
return True
7551
else:
7552
return False
7553
7554
self.wait_and_maintain(
7555
value_name="Climbrate",
7556
target=speed_min,
7557
current_value_getter=lambda: get_climbrate(timeout),
7558
accuracy=(speed_max - speed_min),
7559
validator=lambda value2, target2: validator(value2, target2),
7560
timeout=timeout,
7561
**kwargs
7562
)
7563
7564
def groundspeed(self):
7565
m = self.assert_receive_message('VFR_HUD')
7566
return m.groundspeed
7567
7568
def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs):
7569
self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs)
7570
7571
def wait_airspeed(self, speed_min, speed_max, timeout=30, **kwargs):
7572
self.wait_vfr_hud_speed("airspeed", speed_min, speed_max, timeout=timeout, **kwargs)
7573
7574
def wait_vfr_hud_speed(self, field, speed_min, speed_max, timeout=30, **kwargs):
7575
"""Wait for a given ground speed range."""
7576
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
7577
7578
def get_speed(timeout2):
7579
msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)
7580
return getattr(msg, field)
7581
7582
self.wait_and_maintain_range(
7583
value_name=field,
7584
minimum=speed_min,
7585
maximum=speed_max,
7586
current_value_getter=lambda: get_speed(timeout),
7587
validator=None,
7588
timeout=timeout,
7589
**kwargs
7590
)
7591
7592
def wait_roll(self, roll, accuracy, timeout=30, absolute_value=False, **kwargs):
7593
"""Wait for a given roll in degrees."""
7594
def get_roll(timeout2):
7595
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7596
p = math.degrees(msg.pitch)
7597
r = math.degrees(msg.roll)
7598
if absolute_value:
7599
r = abs(r)
7600
self.progress("Roll %d Pitch %d" % (r, p))
7601
return r
7602
7603
def validator(value2, target2):
7604
return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy
7605
7606
self.wait_and_maintain(
7607
value_name="Roll",
7608
target=roll,
7609
current_value_getter=lambda: get_roll(timeout),
7610
validator=lambda value2, target2: validator(value2, target2),
7611
accuracy=accuracy,
7612
timeout=timeout,
7613
**kwargs
7614
)
7615
7616
def wait_pitch(self, pitch, accuracy, timeout=30, **kwargs):
7617
"""Wait for a given pitch in degrees."""
7618
def get_pitch(timeout2):
7619
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7620
p = math.degrees(msg.pitch)
7621
r = math.degrees(msg.roll)
7622
self.progress("Pitch %d Roll %d" % (p, r))
7623
return p
7624
7625
def validator(value2, target2):
7626
return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy
7627
7628
self.wait_and_maintain(
7629
value_name="Pitch",
7630
target=pitch,
7631
current_value_getter=lambda: get_pitch(timeout),
7632
validator=lambda value2, target2: validator(value2, target2),
7633
accuracy=accuracy,
7634
timeout=timeout,
7635
**kwargs
7636
)
7637
7638
def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs):
7639
if isinstance(target, Vector3):
7640
return self.wait_and_maintain_vector(
7641
value_name,
7642
target,
7643
current_value_getter,
7644
validator,
7645
timeout=30,
7646
**kwargs
7647
)
7648
return self.wait_and_maintain_range(
7649
value_name,
7650
minimum=target - accuracy,
7651
maximum=target + accuracy,
7652
current_value_getter=current_value_getter,
7653
validator=validator,
7654
timeout=timeout,
7655
print_diagnostics_as_target_not_range=True,
7656
**kwargs
7657
)
7658
7659
def wait_and_maintain_vector(self,
7660
value_name,
7661
target,
7662
current_value_getter,
7663
validator,
7664
timeout=30,
7665
**kwargs):
7666
tstart = self.get_sim_time()
7667
achieving_duration_start = None
7668
sum_of_achieved_values = Vector3()
7669
last_value = Vector3()
7670
last_fail_print = 0
7671
count_of_achieved_values = 0
7672
called_function = kwargs.get("called_function", None)
7673
minimum_duration = kwargs.get("minimum_duration", 0)
7674
if minimum_duration >= timeout:
7675
raise ValueError("minimum_duration >= timeout")
7676
7677
self.progress("Waiting for %s=(%s)" % (value_name, str(target)))
7678
7679
last_print_time = 0
7680
while True: # if we failed to received message with the getter the sim time isn't updated # noqa
7681
now = self.get_sim_time_cached()
7682
if now - tstart > timeout:
7683
raise AutoTestTimeoutException(
7684
"Failed to attain %s want %s, reached %s" %
7685
(value_name,
7686
str(target),
7687
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) # noqa
7688
7689
last_value = current_value_getter()
7690
if called_function is not None:
7691
called_function(last_value, target)
7692
is_value_valid = validator(last_value, target)
7693
if self.get_sim_time_cached() - last_print_time > 1:
7694
if is_value_valid:
7695
want_or_got = "got"
7696
else:
7697
want_or_got = "want"
7698
achieved_duration_bit = ""
7699
if achieving_duration_start is not None:
7700
so_far = self.get_sim_time_cached() - achieving_duration_start
7701
achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)
7702
self.progress(
7703
"%s=(%s) (%s (%s))%s" %
7704
(value_name,
7705
str(last_value),
7706
want_or_got,
7707
str(target),
7708
achieved_duration_bit)
7709
)
7710
last_print_time = self.get_sim_time_cached()
7711
if is_value_valid:
7712
sum_of_achieved_values += last_value
7713
count_of_achieved_values += 1.0
7714
if achieving_duration_start is None:
7715
achieving_duration_start = self.get_sim_time_cached()
7716
if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:
7717
self.progress("Attained %s=%s" % (
7718
value_name,
7719
str(sum_of_achieved_values * (1.0 / count_of_achieved_values))))
7720
return True
7721
else:
7722
achieving_duration_start = None
7723
sum_of_achieved_values.zero()
7724
count_of_achieved_values = 0
7725
if now - last_fail_print > 1:
7726
self.progress("Waiting for (%s), got %s" %
7727
(target, last_value))
7728
last_fail_print = now
7729
7730
def validate_kwargs(self, kwargs, valid: dict | None = None):
7731
if valid is None:
7732
valid = {}
7733
for key in kwargs:
7734
if key not in valid:
7735
raise NotAchievedException("Invalid kwarg %s" % str(key))
7736
7737
def wait_and_maintain_range(self,
7738
value_name,
7739
minimum,
7740
maximum,
7741
current_value_getter,
7742
validator=None,
7743
value_averager=None,
7744
timeout=30,
7745
print_diagnostics_as_target_not_range=False,
7746
**kwargs):
7747
self.validate_kwargs(kwargs, valid=frozenset([
7748
"called_function",
7749
"minimum_duration",
7750
"altitude_source",
7751
]))
7752
7753
if print_diagnostics_as_target_not_range:
7754
target = (minimum + maximum) / 2
7755
accuracy = (maximum - minimum) / 2
7756
tstart = self.get_sim_time()
7757
achieving_duration_start = None
7758
sum_of_achieved_values = 0.0
7759
last_value = 0.0
7760
count_of_achieved_values = 0
7761
called_function = kwargs.get("called_function", None)
7762
minimum_duration = kwargs.get("minimum_duration", 0)
7763
if minimum_duration >= timeout:
7764
raise ValueError("minimum_duration >= timeout")
7765
if print_diagnostics_as_target_not_range:
7766
self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy))
7767
else:
7768
self.progress("Waiting for %s between (%s) and (%s)" % (value_name, str(minimum), str(maximum)))
7769
last_print_time = 0
7770
while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa
7771
last_value = current_value_getter()
7772
if called_function is not None:
7773
if print_diagnostics_as_target_not_range:
7774
called_function(last_value, target)
7775
else:
7776
called_function(last_value, minimum, maximum)
7777
if validator is not None:
7778
if print_diagnostics_as_target_not_range:
7779
is_value_valid = validator(last_value, target)
7780
else:
7781
is_value_valid = validator(last_value, minimum, maximum)
7782
else:
7783
is_value_valid = (minimum <= last_value) and (last_value <= maximum)
7784
if self.get_sim_time_cached() - last_print_time > 1:
7785
if is_value_valid:
7786
want_or_got = "got"
7787
else:
7788
want_or_got = "want"
7789
achieved_duration_bit = ""
7790
if achieving_duration_start is not None:
7791
so_far = self.get_sim_time_cached() - achieving_duration_start
7792
achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)
7793
7794
if print_diagnostics_as_target_not_range:
7795
self.progress(
7796
"%s=%0.2f (%s %f +- %f)%s" %
7797
(value_name,
7798
last_value,
7799
want_or_got,
7800
target,
7801
accuracy,
7802
achieved_duration_bit)
7803
)
7804
else:
7805
if isinstance(last_value, float):
7806
self.progress(
7807
"%s=%0.2f (%s between %s and %s)%s" %
7808
(value_name,
7809
last_value,
7810
want_or_got,
7811
str(minimum),
7812
str(maximum),
7813
achieved_duration_bit)
7814
)
7815
else:
7816
self.progress(
7817
"%s=%s (%s between %s and %s)%s" %
7818
(value_name,
7819
last_value,
7820
want_or_got,
7821
str(minimum),
7822
str(maximum),
7823
achieved_duration_bit)
7824
)
7825
last_print_time = self.get_sim_time_cached()
7826
if is_value_valid:
7827
if value_averager is not None:
7828
average = value_averager.add_value(last_value)
7829
else:
7830
sum_of_achieved_values += last_value
7831
count_of_achieved_values += 1.0
7832
average = sum_of_achieved_values / count_of_achieved_values
7833
if achieving_duration_start is None:
7834
achieving_duration_start = self.get_sim_time_cached()
7835
if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:
7836
self.progress("Attained %s=%s" % (value_name, average))
7837
return True
7838
else:
7839
achieving_duration_start = None
7840
sum_of_achieved_values = 0.0
7841
count_of_achieved_values = 0
7842
if value_averager is not None:
7843
value_averager.reset()
7844
if print_diagnostics_as_target_not_range:
7845
raise AutoTestTimeoutException(
7846
"Failed to attain %s want %s, reached %s" %
7847
(value_name,
7848
str(target),
7849
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))
7850
else:
7851
raise AutoTestTimeoutException(
7852
"Failed to attain %s between %s and %s, reached %s" %
7853
(value_name,
7854
str(minimum),
7855
str(maximum),
7856
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))
7857
7858
def heading_delta(self, heading1, heading2):
7859
'''return angle between two 0-360 headings'''
7860
return math.fabs((heading1 - heading2 + 180) % 360 - 180)
7861
7862
def get_heading(self, timeout=1):
7863
'''return heading 0-359'''
7864
m = self.assert_receive_message('VFR_HUD', timeout=timeout)
7865
return m.heading
7866
7867
def wait_heading(self, heading, accuracy=5, timeout=30, **kwargs):
7868
"""Wait for a given heading."""
7869
def get_heading_wrapped(timeout2):
7870
return self.get_heading(timeout=timeout2)
7871
7872
def validator(value2, target2):
7873
return self.heading_delta(value2, target2) <= accuracy
7874
7875
self.wait_and_maintain(
7876
value_name="Heading",
7877
target=heading,
7878
current_value_getter=lambda: get_heading_wrapped(timeout),
7879
validator=lambda value2, target2: validator(value2, target2),
7880
accuracy=accuracy,
7881
timeout=timeout,
7882
**kwargs
7883
)
7884
7885
def wait_yaw_speed(self, yaw_speed, accuracy=0.1, timeout=30, **kwargs):
7886
"""Wait for a given yaw speed in radians per second."""
7887
def get_yawspeed(timeout2):
7888
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7889
return msg.yawspeed
7890
7891
def validator(value2, target2):
7892
return math.fabs(value2 - target2) <= accuracy
7893
7894
self.wait_and_maintain(
7895
value_name="YawSpeed",
7896
target=yaw_speed,
7897
current_value_getter=lambda: get_yawspeed(timeout),
7898
validator=lambda value2, target2: validator(value2, target2),
7899
accuracy=accuracy,
7900
timeout=timeout,
7901
**kwargs
7902
)
7903
7904
def get_speed_vector(self, timeout=1):
7905
'''return speed vector, NED'''
7906
msg = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)
7907
return Vector3(msg.vx, msg.vy, msg.vz)
7908
7909
"""Wait for a given speed vector."""
7910
def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs):
7911
def validator(value2, target2):
7912
for (want, got) in (target2.x, value2.x), (target2.y, value2.y), (target2.z, value2.z):
7913
if want != float("nan") and (math.fabs(got - want) > accuracy):
7914
return False
7915
return True
7916
7917
self.wait_and_maintain(
7918
value_name="SpeedVector",
7919
target=speed_vector,
7920
current_value_getter=lambda: self.get_speed_vector(timeout=timeout),
7921
validator=lambda value2, target2: validator(value2, target2),
7922
accuracy=accuracy,
7923
timeout=timeout,
7924
**kwargs
7925
)
7926
7927
def get_descent_rate(self):
7928
'''get descent rate - a positive number if you are going down'''
7929
return abs(self.get_speed_vector().z)
7930
7931
def wait_descent_rate(self, rate, accuracy=0.1, **kwargs):
7932
'''wait for descent rate rate, a positive number if going down'''
7933
def validator(value, target):
7934
return math.fabs(value - target) <= accuracy
7935
7936
self.wait_and_maintain(
7937
value_name="DescentRate",
7938
target=rate,
7939
current_value_getter=lambda: self.get_descent_rate(),
7940
validator=lambda value, target: validator(value, target),
7941
accuracy=accuracy,
7942
**kwargs
7943
)
7944
7945
def get_body_frame_velocity(self):
7946
gri = self.assert_receive_message('GPS_RAW_INT')
7947
att = self.assert_receive_message('ATTITUDE')
7948
return mavextra.gps_velocity_body(gri, att)
7949
7950
def wait_speed_vector_bf(self, speed_vector, accuracy=0.2, timeout=30, **kwargs):
7951
"""Wait for a given speed vector."""
7952
def get_speed_vector(timeout2):
7953
return self.get_body_frame_velocity()
7954
7955
def validator(value2, target2):
7956
return (math.fabs(value2.x - target2.x) <= accuracy and
7957
math.fabs(value2.y - target2.y) <= accuracy and
7958
math.fabs(value2.z - target2.z) <= accuracy)
7959
7960
self.wait_and_maintain(
7961
value_name="SpeedVectorBF",
7962
target=speed_vector,
7963
current_value_getter=lambda: get_speed_vector(timeout),
7964
validator=lambda value2, target2: validator(value2, target2),
7965
accuracy=accuracy,
7966
timeout=timeout,
7967
**kwargs
7968
)
7969
7970
def wait_distance_between(self, series1, series2, min_distance, max_distance, timeout=30, **kwargs):
7971
"""Wait for distance between two position series to be between two thresholds."""
7972
def get_distance():
7973
self.drain_mav()
7974
m1 = self.mav.messages[series1]
7975
m2 = self.mav.messages[series2]
7976
return self.get_distance_int(m1, m2)
7977
7978
self.wait_and_maintain_range(
7979
value_name=f"Distance({series1}, {series2})",
7980
minimum=min_distance,
7981
maximum=max_distance,
7982
current_value_getter=lambda: get_distance(),
7983
timeout=timeout,
7984
**kwargs
7985
)
7986
7987
def wait_distance(self, distance, accuracy=2, timeout=30, **kwargs):
7988
"""Wait for flight of a given distance."""
7989
start = self.mav.location()
7990
7991
def get_distance():
7992
return self.get_distance(start, self.mav.location())
7993
7994
def validator(value2, target2):
7995
return math.fabs(value2 - target2) <= accuracy
7996
7997
self.wait_and_maintain(
7998
value_name="Distance",
7999
target=distance,
8000
current_value_getter=lambda: get_distance(),
8001
validator=lambda value2, target2: validator(value2, target2),
8002
accuracy=accuracy,
8003
timeout=timeout,
8004
**kwargs
8005
)
8006
8007
def wait_distance_to_waypoint(self, wp_num, distance_min, distance_max, **kwargs):
8008
# TODO: use mission_request_partial_list_send
8009
wps = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
8010
m = wps[wp_num]
8011
self.progress("m: %s" % str(m))
8012
loc = mavutil.location(m.x / 1.0e7, m.y / 1.0e7, 0, 0)
8013
self.progress("loc: %s" % str(loc))
8014
self.wait_distance_to_location(loc, distance_min, distance_max, **kwargs)
8015
8016
def wait_distance_to_location(self, location, distance_min, distance_max, timeout=30, **kwargs):
8017
"""Wait for flight of a given distance."""
8018
assert distance_min <= distance_max, "Distance min should be less than distance max."
8019
8020
def get_distance():
8021
return self.get_distance(location, self.mav.location())
8022
8023
def validator(value2, target2=None):
8024
return distance_min <= value2 <= distance_max
8025
8026
self.wait_and_maintain(
8027
value_name="Distance",
8028
target=distance_min,
8029
current_value_getter=lambda: get_distance(),
8030
validator=lambda value2, target2: validator(value2, target2),
8031
accuracy=(distance_max - distance_min), timeout=timeout,
8032
**kwargs
8033
)
8034
8035
def wait_distance_to_home(self, distance_min, distance_max, timeout=10, use_cached_home=True, **kwargs):
8036
"""Wait for distance to home to be within specified bounds."""
8037
assert distance_min <= distance_max, "Distance min should be less than distance max."
8038
8039
def get_distance():
8040
return self.distance_to_home(use_cached_home)
8041
8042
def validator(value2, target2=None):
8043
return distance_min <= value2 <= distance_max
8044
8045
self.wait_and_maintain(
8046
value_name="Distance to home",
8047
target=distance_min,
8048
current_value_getter=lambda: get_distance(),
8049
validator=lambda value2, target2: validator(value2, target2),
8050
accuracy=(distance_max - distance_min), timeout=timeout,
8051
**kwargs
8052
)
8053
8054
def assert_at_home(self, accuracy=1):
8055
if self.distance_to_home() > accuracy:
8056
raise NotAchievedException("Not at home")
8057
8058
def wait_distance_to_nav_target(self,
8059
distance_min,
8060
distance_max,
8061
timeout=10,
8062
use_cached_nav_controller_output=False,
8063
**kwargs):
8064
"""Wait for distance to home to be within specified bounds."""
8065
assert distance_min <= distance_max, "Distance min should be less than distance max."
8066
8067
def get_distance():
8068
return self.distance_to_nav_target(use_cached_nav_controller_output)
8069
8070
def validator(value2, target2=None):
8071
return distance_min <= value2 <= distance_max
8072
8073
self.wait_and_maintain(
8074
value_name="Distance to nav target",
8075
target=distance_min,
8076
current_value_getter=lambda: get_distance(),
8077
validator=lambda value2,
8078
target2: validator(value2, target2),
8079
accuracy=(distance_max - distance_min),
8080
timeout=timeout,
8081
**kwargs
8082
)
8083
8084
def get_local_position_NED(self):
8085
'''return a Vector3 repreesenting vehicle position relative to
8086
origin in metres, NED'''
8087
pos = self.assert_receive_message('LOCAL_POSITION_NED')
8088
return Vector3(pos.x, pos.y, pos.z)
8089
8090
def distance_to_local_position(self, local_pos, timeout=30):
8091
(x, y, z_down) = local_pos # alt is *up*
8092
8093
pos = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)
8094
8095
delta_x = pos.x - x
8096
delta_y = pos.y - y
8097
delta_z = pos.z - z_down
8098
return math.sqrt(delta_x*delta_x + delta_y*delta_y + delta_z*delta_z)
8099
8100
def wait_distance_to_local_position(self,
8101
local_position, # (x, y, z_down)
8102
distance_min,
8103
distance_max,
8104
timeout=10,
8105
**kwargs):
8106
"""Wait for distance to home to be within specified bounds."""
8107
assert distance_min <= distance_max, "Distance min should be less than distance max."
8108
8109
def get_distance():
8110
return self.distance_to_local_position(local_position)
8111
8112
def validator(value2, target2=None):
8113
return distance_min <= value2 <= distance_max
8114
8115
(x, y, z_down) = local_position
8116
self.wait_and_maintain(
8117
value_name="Distance to (%f,%f,%f)" % (x, y, z_down),
8118
target=distance_min,
8119
current_value_getter=lambda: get_distance(),
8120
validator=lambda value2,
8121
target2: validator(value2, target2),
8122
accuracy=(distance_max - distance_min),
8123
timeout=timeout,
8124
**kwargs
8125
)
8126
8127
def wait_parameter_value(self, parameter, value, timeout=10):
8128
tstart = self.get_sim_time()
8129
while True:
8130
if self.get_sim_time_cached() - tstart > timeout:
8131
raise NotAchievedException("%s never got value %f" %
8132
(parameter, value))
8133
v = self.get_parameter(parameter, verbose=False)
8134
self.progress("Got parameter value (%s=%f)" %
8135
(parameter, v))
8136
if v == value:
8137
return
8138
self.delay_sim_time(0.1)
8139
8140
def wait_parameter_values(self, parameters, timeout=10):
8141
need_to_see = copy.copy(parameters)
8142
tstart = self.get_sim_time()
8143
while True:
8144
if self.get_sim_time_cached() - tstart > timeout:
8145
raise NotAchievedException(f"Parameters did not get values: {need_to_see}")
8146
new_values = self.get_parameters(need_to_see.keys())
8147
for (n, v) in new_values.items():
8148
self.progress(f"Got parameter value ({n}={v}) want={need_to_see[n]}")
8149
if need_to_see[n] == v:
8150
del need_to_see[n]
8151
if len(need_to_see) == 0:
8152
break
8153
8154
def get_servo_channel_value(self, channel, timeout=2):
8155
channel_field = "servo%u_raw" % channel
8156
tstart = self.get_sim_time()
8157
while True:
8158
remaining = timeout - (self.get_sim_time_cached() - tstart)
8159
if remaining <= 0:
8160
raise NotAchievedException("Channel value condition not met")
8161
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
8162
blocking=True,
8163
timeout=remaining)
8164
if m is None:
8165
continue
8166
m_value = getattr(m, channel_field, None)
8167
if m_value is None:
8168
raise ValueError("message (%s) has no field %s" %
8169
(str(m), channel_field))
8170
return m_value
8171
8172
def wait_servo_channel_value(self, channel, value, epsilon=0, timeout=2, comparator=operator.eq):
8173
"""wait for channel value comparison (default condition is equality)"""
8174
channel_field = "servo%u_raw" % channel
8175
opstring = ("%s" % comparator)[-3:-1]
8176
tstart = self.get_sim_time()
8177
while True:
8178
remaining = timeout - (self.get_sim_time_cached() - tstart)
8179
if remaining <= 0:
8180
raise NotAchievedException("Channel value condition not met")
8181
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
8182
blocking=True,
8183
timeout=remaining)
8184
if m is None:
8185
continue
8186
m_value = getattr(m, channel_field, None)
8187
if m_value is None:
8188
raise ValueError("message (%s) has no field %s" %
8189
(str(m), channel_field))
8190
self.progress("SERVO_OUTPUT_RAW.%s got=%u %s want=%u" %
8191
(channel_field, m_value, opstring, value))
8192
if comparator == operator.eq:
8193
if abs(m_value - value) <= epsilon:
8194
return m_value
8195
if comparator(m_value, value):
8196
return m_value
8197
8198
def wait_servo_channel_in_range(self, channel, v_min, v_max, timeout=2):
8199
"""wait for channel value to be within acceptable range"""
8200
channel_field = "servo%u_raw" % channel
8201
tstart = self.get_sim_time()
8202
while True:
8203
remaining = timeout - (self.get_sim_time_cached() - tstart)
8204
if remaining <= 0:
8205
raise NotAchievedException("Channel value condition not met")
8206
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
8207
blocking=True,
8208
timeout=remaining)
8209
if m is None:
8210
continue
8211
m_value = getattr(m, channel_field, None)
8212
if m_value is None:
8213
raise ValueError("message (%s) has no field %s" %
8214
(str(m), channel_field))
8215
self.progress("want %u <= SERVO_OUTPUT_RAW.%s <= %u, got value = %u" %
8216
(v_min, channel_field, v_max, m_value))
8217
if (v_min <= m_value) and (m_value <= v_max):
8218
return m_value
8219
8220
def assert_servo_channel_value(self, channel, value, comparator=operator.eq):
8221
"""assert channel value (default condition is equality)"""
8222
channel_field = "servo%u_raw" % channel
8223
opstring = ("%s" % comparator)[-3:-1]
8224
m = self.assert_receive_message('SERVO_OUTPUT_RAW')
8225
m_value = getattr(m, channel_field, None)
8226
if m_value is None:
8227
raise ValueError("message (%s) has no field %s" %
8228
(str(m), channel_field))
8229
self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" %
8230
(channel_field, m_value, opstring, value))
8231
if comparator(m_value, value):
8232
return m_value
8233
raise NotAchievedException("Wrong value")
8234
8235
def assert_servo_channel_range(self, channel, value_min, value_max):
8236
"""assert channel value is within the range [value_min, value_max]"""
8237
channel_field = "servo%u_raw" % channel
8238
m = self.assert_receive_message('SERVO_OUTPUT_RAW')
8239
m_value = getattr(m, channel_field, None)
8240
if m_value is None:
8241
raise ValueError("message (%s) has no field %s" %
8242
(str(m), channel_field))
8243
self.progress("assert SERVO_OUTPUT_RAW.%s=%u in [%u, %u]" %
8244
(channel_field, m_value, value_min, value_max))
8245
if m_value >= value_min and m_value <= value_max:
8246
return m_value
8247
raise NotAchievedException("Wrong value")
8248
8249
def get_rc_channel_value(self, channel, timeout=2):
8250
"""wait for channel to hit value"""
8251
channel_field = "chan%u_raw" % channel
8252
tstart = self.get_sim_time()
8253
while True:
8254
remaining = timeout - (self.get_sim_time_cached() - tstart)
8255
if remaining <= 0:
8256
raise NotAchievedException("Channel never achieved value")
8257
m = self.mav.recv_match(type='RC_CHANNELS',
8258
blocking=True,
8259
timeout=remaining)
8260
if m is None:
8261
continue
8262
m_value = getattr(m, channel_field)
8263
if m_value is None:
8264
raise ValueError("message (%s) has no field %s" %
8265
(str(m), channel_field))
8266
return m_value
8267
8268
def wait_rc_channel_value(self, channel, value, timeout=2):
8269
channel_field = "chan%u_raw" % channel
8270
tstart = self.get_sim_time()
8271
while True:
8272
remaining = timeout - (self.get_sim_time_cached() - tstart)
8273
if remaining <= 0:
8274
raise NotAchievedException("Channel never achieved value")
8275
m_value = self.get_rc_channel_value(channel, timeout=timeout)
8276
self.progress("RC_CHANNELS.%s=%u want=%u" %
8277
(channel_field, m_value, value))
8278
if value == m_value:
8279
return
8280
8281
def assert_rc_channel_value(self, channel, value):
8282
channel_field = "chan%u_raw" % channel
8283
8284
m_value = self.get_rc_channel_value(channel, timeout=1)
8285
self.progress("RC_CHANNELS.%s=%u want=%u" %
8286
(channel_field, m_value, value))
8287
if value != m_value:
8288
raise NotAchievedException("Expected %s to be %u got %u" %
8289
(channel, value, m_value))
8290
8291
def send_do_reposition(self,
8292
loc,
8293
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT):
8294
'''send a DO_REPOSITION command for a location'''
8295
self.run_cmd_int(
8296
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
8297
0,
8298
0,
8299
0,
8300
0,
8301
int(loc.lat*1e7), # lat* 1e7
8302
int(loc.lng*1e7), # lon* 1e7
8303
loc.alt,
8304
frame=frame
8305
)
8306
8307
def add_rally_point(self, loc, seq, total):
8308
'''add a rally point at the given location'''
8309
self.mav.mav.rally_point_send(1, # target system
8310
0, # target component
8311
seq, # sequence number
8312
total, # total count
8313
int(loc.lat * 1e7),
8314
int(loc.lng * 1e7),
8315
loc.alt, # relative alt
8316
0, # "break" alt?!
8317
0, # "land dir"
8318
0) # flags
8319
8320
def wait_location(self, loc, **kwargs):
8321
waiter = WaitAndMaintainLocation(self, loc, **kwargs)
8322
waiter.run()
8323
8324
def assert_current_waypoint(self, wpnum):
8325
seq = self.mav.waypoint_current()
8326
if seq != wpnum:
8327
raise NotAchievedException("Incorrect current wp")
8328
8329
def wait_current_waypoint(self, wpnum, timeout=70):
8330
tstart = self.get_sim_time()
8331
while True:
8332
if self.get_sim_time() - tstart > timeout:
8333
raise AutoTestTimeoutException("Did not get wanted current waypoint")
8334
seq = self.mav.waypoint_current()
8335
wp_dist = None
8336
try:
8337
wp_dist = self.mav.messages['NAV_CONTROLLER_OUTPUT'].wp_dist
8338
except (KeyError, AttributeError):
8339
pass
8340
self.progress("Waiting for wp=%u current=%u dist=%sm" % (wpnum, seq, wp_dist))
8341
if seq == wpnum:
8342
break
8343
8344
def wait_waypoint(self,
8345
wpnum_start,
8346
wpnum_end,
8347
allow_skip=True,
8348
max_dist=2,
8349
timeout=400,
8350
ignore_RTL_mode_change=False,
8351
ignore_MANUAL_mode_change=False,
8352
):
8353
"""Wait for waypoint ranges."""
8354
tstart = self.get_sim_time()
8355
# this message arrives after we set the current WP
8356
start_wp = self.mav.waypoint_current()
8357
current_wp = start_wp
8358
mode = self.mav.flightmode
8359
8360
self.progress("wait for waypoint ranges start=%u end=%u"
8361
% (wpnum_start, wpnum_end))
8362
# if start_wp != wpnum_start:
8363
# raise WaitWaypointTimeout("test: Expected start waypoint %u "
8364
# "but got %u" %
8365
# (wpnum_start, start_wp))
8366
8367
last_wp_msg = 0
8368
while self.get_sim_time_cached() < tstart + timeout:
8369
seq = self.mav.waypoint_current()
8370
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT')
8371
wp_dist = m.wp_dist
8372
m = self.assert_receive_message('VFR_HUD')
8373
8374
# if we changed mode, fail
8375
if not self.mode_is('AUTO'):
8376
self.progress(f"{self.mav.flightmode} vs {self.get_mode_from_mode_mapping(mode)}")
8377
ignore_mode_change = (
8378
(ignore_RTL_mode_change and self.mode_is('RTL', cached=True)) or
8379
(ignore_MANUAL_mode_change and self.mode_is('MANUAL', cached=True))
8380
)
8381
if not ignore_mode_change:
8382
new_mode_str = self.get_mode_string_for_mode(self.get_mode())
8383
raise WaitWaypointTimeout(f'Exited {mode} mode to {new_mode_str} ignore={ignore_RTL_mode_change}')
8384
8385
if self.get_sim_time_cached() - last_wp_msg > 1:
8386
self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u,"
8387
"wpnum_end: %u" %
8388
(seq, wp_dist, m.alt, current_wp, wpnum_end))
8389
last_wp_msg = self.get_sim_time_cached()
8390
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
8391
self.progress("WW: Starting new waypoint %u" % seq)
8392
tstart = self.get_sim_time()
8393
current_wp = seq
8394
# the wp_dist check is a hack until we can sort out
8395
# the right seqnum for end of mission
8396
# if current_wp == wpnum_end or (current_wp == wpnum_end-1 and
8397
# wp_dist < 2):
8398
if current_wp == wpnum_end and wp_dist < max_dist:
8399
self.progress("Reached final waypoint %u" % seq)
8400
return True
8401
if seq >= 255:
8402
self.progress("Reached final waypoint %u" % seq)
8403
return True
8404
if seq > current_wp+1:
8405
raise WaitWaypointTimeout(("Skipped waypoint! Got wp %u expected %u"
8406
% (seq, current_wp+1)))
8407
raise WaitWaypointTimeout("Timed out waiting for waypoint %u of %u" %
8408
(wpnum_end, wpnum_end))
8409
8410
def get_cached_message(self, message_type):
8411
'''returns the most-recently received instance of message_type'''
8412
return self.mav.messages[message_type]
8413
8414
def mode_is(self, mode, cached=False, drain_mav=True, drain_mav_quietly=True):
8415
if not cached:
8416
self.wait_heartbeat(drain_mav=drain_mav, quiet=drain_mav_quietly)
8417
return self.mav.messages['HEARTBEAT'].custom_mode == self.get_mode_from_mode_mapping(mode)
8418
8419
def wait_mode(self, mode, timeout=60):
8420
"""Wait for mode to change."""
8421
self.progress("Waiting for mode %s" % mode)
8422
tstart = self.get_sim_time()
8423
while not self.mode_is(mode, drain_mav=False):
8424
custom_num = self.mav.messages['HEARTBEAT'].custom_mode
8425
self.progress("mav.flightmode=%s Want=%s custom=%u" % (
8426
self.mav.flightmode, mode, custom_num))
8427
if (timeout is not None and
8428
self.get_sim_time_cached() > tstart + timeout):
8429
raise WaitModeTimeout("Did not change mode")
8430
self.progress("Got mode %s" % mode)
8431
8432
def assert_mode_is(self, mode):
8433
if not self.mode_is(mode):
8434
raise NotAchievedException("Expected mode %s" % str(mode))
8435
8436
def get_mode(self, cached=False, drain_mav=True):
8437
'''return numeric custom mode'''
8438
if not cached:
8439
self.wait_heartbeat(drain_mav=drain_mav)
8440
return self.mav.messages['HEARTBEAT'].custom_mode
8441
8442
def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30):
8443
self.progress("Waiting for GPS health")
8444
tstart = self.get_sim_time()
8445
while True:
8446
now = self.get_sim_time_cached()
8447
if now - tstart > timeout:
8448
raise AutoTestTimeoutException("GPS status bits did not become good")
8449
m = self.mav.recv_match(type='SYS_STATUS', blocking=True, timeout=1)
8450
if m is None:
8451
continue
8452
if (not (m.onboard_control_sensors_present & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8453
self.progress("GPS not present")
8454
if now > 20:
8455
# it's had long enough to be detected....
8456
return
8457
continue
8458
if (not (m.onboard_control_sensors_enabled & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8459
self.progress("GPS not enabled")
8460
continue
8461
if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8462
self.progress("GPS not healthy")
8463
continue
8464
self.progress("GPS healthy after %f/%f seconds" %
8465
((now - tstart), timeout))
8466
return
8467
8468
def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False):
8469
return self.sensor_has_state(sensor, present, enabled, healthy, do_assert=True, verbose=verbose)
8470
8471
def sensor_has_state(self, sensor, present=True, enabled=True, healthy=True, do_assert=False, verbose=False):
8472
m = self.assert_receive_message('SYS_STATUS', timeout=5, very_verbose=verbose)
8473
reported_present = m.onboard_control_sensors_present & sensor
8474
reported_enabled = m.onboard_control_sensors_enabled & sensor
8475
reported_healthy = m.onboard_control_sensors_health & sensor
8476
if present:
8477
if not reported_present:
8478
if do_assert:
8479
raise NotAchievedException("Sensor not present")
8480
return False
8481
else:
8482
if reported_present:
8483
if do_assert:
8484
raise NotAchievedException("Sensor present when it shouldn't be")
8485
return False
8486
8487
if enabled:
8488
if not reported_enabled:
8489
if do_assert:
8490
raise NotAchievedException("Sensor not enabled")
8491
return False
8492
else:
8493
if reported_enabled:
8494
if do_assert:
8495
raise NotAchievedException("Sensor enabled when it shouldn't be")
8496
return False
8497
8498
if healthy:
8499
if not reported_healthy:
8500
if do_assert:
8501
raise NotAchievedException("Sensor not healthy")
8502
return False
8503
else:
8504
if reported_healthy:
8505
if do_assert:
8506
raise NotAchievedException("Sensor healthy when it shouldn't be")
8507
return False
8508
return True
8509
8510
def wait_sensor_state(self, sensor, present=True, enabled=True, healthy=True, timeout=5, verbose=False):
8511
tstart = self.get_sim_time()
8512
while True:
8513
if self.get_sim_time_cached() - tstart > timeout:
8514
raise NotAchievedException("Sensor did not achieve state")
8515
if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose):
8516
break
8517
8518
def wait_not_ready_to_arm(self):
8519
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False)
8520
8521
def wait_prearm_sys_status_healthy(self, timeout=60):
8522
self.do_timesync_roundtrip()
8523
tstart = self.get_sim_time()
8524
while True:
8525
t2 = self.get_sim_time_cached()
8526
if t2 - tstart > timeout:
8527
self.progress("Prearm bit never went true. Attempting arm to elicit reason from autopilot")
8528
try:
8529
self.arm_vehicle()
8530
except Exception:
8531
pass
8532
raise AutoTestTimeoutException("Prearm bit never went true")
8533
if self.sensor_has_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, True):
8534
break
8535
8536
def assert_fence_enabled(self, timeout=2):
8537
# Check fence is enabled
8538
m = self.assert_receive_message('FENCE_STATUS', timeout=timeout)
8539
self.progress("Got (%s)" % str(m))
8540
8541
def assert_fence_disabled(self, timeout=2):
8542
# Check fence is not enabled
8543
self.assert_not_receiving_message('FENCE_STATUS', timeout=timeout)
8544
8545
def NoArmWithoutMissionItems(self):
8546
'''ensure we can't arm in auto mode without mission items present'''
8547
# load a trivial mission
8548
items = []
8549
items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 20000),)
8550
items.append((mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0))
8551
self.upload_simple_relhome_mission(items)
8552
8553
self.change_mode('AUTO')
8554
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
8555
self.assert_prearm_failure('Mode requires mission',
8556
other_prearm_failures_fatal=False)
8557
8558
def assert_prearm_failure(self,
8559
expected_statustext,
8560
timeout=5,
8561
ignore_prearm_failures: list | None = None,
8562
other_prearm_failures_fatal=True):
8563
if ignore_prearm_failures is None:
8564
ignore_prearm_failures = []
8565
8566
seen_statustext = False
8567
seen_command_ack = False
8568
8569
self.drain_mav()
8570
tstart = self.get_sim_time_cached()
8571
arm_last_send = 0
8572
while True:
8573
if seen_command_ack and seen_statustext:
8574
break
8575
now = self.get_sim_time_cached()
8576
if now - tstart > timeout:
8577
raise NotAchievedException(
8578
f"Did not see failure-to-arm messages ({seen_statustext=} {expected_statustext=} {seen_command_ack=})"
8579
)
8580
if now - arm_last_send > 1:
8581
arm_last_send = now
8582
self.send_mavlink_run_prearms_command()
8583
m = self.mav.recv_match(blocking=True, timeout=1)
8584
if m is None:
8585
continue
8586
if m.get_type() == "STATUSTEXT":
8587
if expected_statustext in m.text:
8588
self.progress("Got: %s" % str(m))
8589
seen_statustext = True
8590
elif other_prearm_failures_fatal and "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
8591
self.progress("Got: %s" % str(m))
8592
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
8593
8594
if m.get_type() == "COMMAND_ACK":
8595
print("Got: %s" % str(m))
8596
if m.command == mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS:
8597
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
8598
raise NotAchievedException("command-ack says we didn't run prearms")
8599
self.progress("Got: %s" % str(m))
8600
seen_command_ack = True
8601
if self.mav.motors_armed():
8602
raise NotAchievedException("Armed when we shouldn't have")
8603
8604
def assert_arm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures: list = None):
8605
if ignore_prearm_failures is None:
8606
ignore_prearm_failures = []
8607
seen_statustext = False
8608
seen_command_ack = False
8609
8610
self.drain_mav()
8611
tstart = self.get_sim_time_cached()
8612
arm_last_send = 0
8613
while True:
8614
if seen_command_ack and seen_statustext:
8615
break
8616
now = self.get_sim_time_cached()
8617
if now - tstart > timeout:
8618
raise NotAchievedException(
8619
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
8620
(seen_statustext, seen_command_ack))
8621
if now - arm_last_send > 1:
8622
arm_last_send = now
8623
self.send_mavlink_arm_command()
8624
m = self.mav.recv_match(blocking=True, timeout=1)
8625
if m is None:
8626
continue
8627
if m.get_type() == "STATUSTEXT":
8628
if expected_statustext in m.text:
8629
self.progress("Got: %s" % str(m))
8630
seen_statustext = True
8631
elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
8632
self.progress("Got: %s" % str(m))
8633
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
8634
8635
if m.get_type() == "COMMAND_ACK":
8636
print("Got: %s" % str(m))
8637
if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:
8638
if m.result != 4:
8639
raise NotAchievedException("command-ack says we didn't fail to arm")
8640
self.progress("Got: %s" % str(m))
8641
seen_command_ack = True
8642
if self.mav.motors_armed():
8643
raise NotAchievedException("Armed when we shouldn't have")
8644
8645
def wait_ready_to_arm(self, timeout=120, require_absolute=True, check_prearm_bit=True):
8646
# wait for EKF checks to pass
8647
self.progress("Waiting for ready to arm")
8648
start = self.get_sim_time()
8649
self.wait_ekf_happy(timeout=timeout, require_absolute=require_absolute)
8650
if require_absolute:
8651
self.wait_gps_sys_status_not_present_or_enabled_and_healthy()
8652
if require_absolute:
8653
self.poll_home_position()
8654
if check_prearm_bit:
8655
self.wait_prearm_sys_status_healthy(timeout=timeout)
8656
armable_time = self.get_sim_time() - start
8657
self.progress("Took %u seconds to become armable" % armable_time)
8658
self.total_waiting_to_arm_time += armable_time
8659
self.waiting_to_arm_count += 1
8660
8661
def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x):
8662
'''as opposed to mav.wait_heartbeat, raises an exception on timeout.
8663
Also, ignores heartbeats not from our target system'''
8664
if drain_mav:
8665
self.drain_mav(quiet=quiet)
8666
orig_timeout = x.get("timeout", 20)
8667
x["timeout"] = 1
8668
tstart = time.time()
8669
while True:
8670
if time.time() - tstart > orig_timeout and not self.gdb:
8671
if not self.sitl_is_running():
8672
self.progress("SITL is not running")
8673
raise AutoTestTimeoutException("Did not receive heartbeat")
8674
m = self.mav.wait_heartbeat(*args, **x)
8675
if m is None:
8676
continue
8677
if m.get_srcSystem() == self.sysid_thismav():
8678
return m
8679
8680
def wait_ekf_happy(self, require_absolute=True, **kwargs):
8681
"""Wait for EKF to be happy"""
8682
if "timeout" not in kwargs:
8683
kwargs["timeout"] = 45
8684
8685
""" if using SITL estimates directly """
8686
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
8687
return True
8688
8689
# all of these must be set for arming to happen:
8690
required_value = (mavutil.mavlink.EKF_ATTITUDE |
8691
mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ |
8692
mavutil.mavlink.ESTIMATOR_VELOCITY_VERT |
8693
mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL |
8694
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_REL)
8695
# none of these bits must be set for arming to happen:
8696
error_bits = (mavutil.mavlink.ESTIMATOR_CONST_POS_MODE |
8697
mavutil.mavlink.ESTIMATOR_ACCEL_ERROR)
8698
if require_absolute:
8699
required_value |= (mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS |
8700
mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |
8701
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)
8702
error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH
8703
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()
8704
8705
def wait_ekf_flags(self, required_value, error_bits, **kwargs):
8706
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()
8707
8708
def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):
8709
"""Disable GPS and wait for EKF to report the end of assistance from GPS."""
8710
self.set_parameter("SIM_GPS1_ENABLE", 0)
8711
tstart = self.get_sim_time()
8712
8713
""" if using SITL estimates directly """
8714
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
8715
self.progress("GPS disable skipped")
8716
return
8717
8718
# all of these must NOT be set for arming NOT to happen:
8719
not_required_value = 0
8720
if position_horizontal:
8721
not_required_value |= mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL
8722
if position_vertical:
8723
not_required_value |= mavutil.mavlink.ESTIMATOR_POS_VERT_AGL
8724
self.progress("Waiting for EKF not having bits %u" % not_required_value)
8725
last_print_time = 0
8726
while timeout is None or self.get_sim_time_cached() < tstart + timeout:
8727
esr = self.assert_receive_message('EKF_STATUS_REPORT', timeout=timeout)
8728
current = esr.flags
8729
if self.get_sim_time_cached() - last_print_time > 1:
8730
self.progress("Wait EKF.flags: not required:%u current:%u" %
8731
(not_required_value, current))
8732
last_print_time = self.get_sim_time_cached()
8733
if current & not_required_value != not_required_value:
8734
self.progress("GPS disable OK")
8735
return
8736
self.progress(f"Last EKF_STATUS_REPORT: {esr}")
8737
raise AutoTestTimeoutException("Failed to get EKF.flags=%u disabled" % not_required_value)
8738
8739
def wait_text(self, *args, **kwargs):
8740
'''wait for text to appear from vehicle, return that text'''
8741
statustext = self.wait_statustext(*args, **kwargs)
8742
if statustext is None:
8743
return None
8744
return statustext.text
8745
8746
def statustext_in_collections(self, text, regex=False):
8747
'''searches for text in STATUSTEXT collection, returns message if found'''
8748
c = self.context_get()
8749
if "STATUSTEXT" not in c.collections:
8750
raise NotAchievedException("Asked to check context but it isn't collecting!")
8751
for x in c.collections["STATUSTEXT"]:
8752
self.progress(" statustext got=(%s) want=(%s)" % (x.text, text))
8753
if regex:
8754
if re.match(text, x.text):
8755
return x
8756
elif text.lower() in x.text.lower():
8757
return x
8758
return None
8759
8760
def wait_statustext(self, text, timeout=20, the_function=None, check_context=False, regex=False, wallclock_timeout=False):
8761
"""Wait for a specific STATUSTEXT, return that statustext message"""
8762
8763
# Statustexts are often triggered by something we've just
8764
# done, so we have to be careful not to read any traffic that
8765
# isn't checked for being our statustext. That doesn't work
8766
# well with getting the current simulation time (which requires
8767
# a new SYSTEM_TIME message), so we install a message hook
8768
# which checks all incoming messages.
8769
self.progress("Waiting for text : %s" % text.lower())
8770
if check_context:
8771
statustext = self.statustext_in_collections(text, regex=regex)
8772
if statustext:
8773
self.progress("Found expected text in collection: %s" % text.lower())
8774
return statustext
8775
8776
global statustext_found
8777
global statustext_full
8778
statustext_full = None
8779
statustext_found = False
8780
8781
def mh(mav, m):
8782
global statustext_found
8783
global statustext_full
8784
if m.get_type() != "STATUSTEXT":
8785
return
8786
if regex:
8787
self.re_match = re.match(text, m.text)
8788
if self.re_match:
8789
statustext_found = True
8790
statustext_full = m
8791
if text.lower() in m.text.lower():
8792
self.progress("Received expected text: %s" % m.text.lower())
8793
statustext_found = True
8794
statustext_full = m
8795
8796
self.install_message_hook(mh)
8797
if wallclock_timeout:
8798
tstart = time.time()
8799
else:
8800
tstart = self.get_sim_time()
8801
try:
8802
while not statustext_found:
8803
if wallclock_timeout:
8804
now = time.time()
8805
else:
8806
now = self.get_sim_time_cached()
8807
if now - tstart > timeout:
8808
raise AutoTestTimeoutException("Failed to receive text: %s" %
8809
text.lower())
8810
if the_function is not None:
8811
the_function()
8812
self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)
8813
finally:
8814
self.remove_message_hook(mh)
8815
return statustext_full
8816
8817
# routines helpful for testing LUA scripting:
8818
def script_example_source_path(self, scriptname):
8819
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "examples", scriptname)
8820
8821
def script_test_source_path(self, scriptname):
8822
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", scriptname)
8823
8824
def script_applet_source_path(self, scriptname):
8825
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "applets", scriptname)
8826
8827
def script_modules_source_path(self, scriptname):
8828
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "modules", scriptname)
8829
8830
def installed_script_path(self, scriptname):
8831
return os.path.join("scripts", os.path.basename(scriptname))
8832
8833
def install_script(self, source, scriptname, install_name=None):
8834
if install_name is not None:
8835
dest = self.installed_script_path(install_name)
8836
else:
8837
dest = self.installed_script_path(scriptname)
8838
8839
destdir = os.path.dirname(dest)
8840
if not os.path.exists(destdir):
8841
os.mkdir(destdir)
8842
self.progress("Copying (%s) to (%s)" % (source, dest))
8843
shutil.copy(source, dest)
8844
8845
def installed_script_module_path(self, modulename):
8846
return os.path.join("scripts", "modules", os.path.basename(modulename))
8847
8848
def install_script_module(self, source, modulename, install_name=None):
8849
if install_name is not None:
8850
dest = self.installed_script_module_path(install_name)
8851
else:
8852
dest = self.installed_script_module_path(modulename)
8853
8854
destdir = os.path.dirname(dest)
8855
os.makedirs(destdir, exist_ok=True)
8856
self.progress("Copying (%s) to (%s)" % (source, dest))
8857
shutil.copy(source, dest)
8858
8859
def install_test_modules(self):
8860
source = os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", "modules", "test")
8861
dest = os.path.join("scripts", "modules", "test")
8862
self.progress("Copying (%s) to (%s)" % (source, dest))
8863
shutil.copytree(source, dest)
8864
8865
def install_mavlink_module(self):
8866
dest = os.path.join("scripts", "modules", "mavlink")
8867
ardupilotmega_xml = os.path.join(self.rootdir(), "modules", "mavlink",
8868
"message_definitions", "v1.0", "ardupilotmega.xml")
8869
mavgen.mavgen(mavgen.Opts(output=dest, wire_protocol='2.0', language='Lua'), [ardupilotmega_xml])
8870
self.progress("Installed mavlink module")
8871
8872
def install_script_content(self, scriptname, content):
8873
dest = self.installed_script_path(scriptname)
8874
destdir = os.path.dirname(dest)
8875
if not os.path.exists(destdir):
8876
os.mkdir(destdir)
8877
destPath = pathlib.Path(dest)
8878
destPath.write_text(content)
8879
8880
def install_example_script(self, scriptname):
8881
source = self.script_example_source_path(scriptname)
8882
self.install_script(source, scriptname)
8883
8884
def install_test_script(self, scriptname):
8885
source = self.script_test_source_path(scriptname)
8886
self.install_script(source, scriptname)
8887
8888
def install_applet_script(self, scriptname, install_name=None):
8889
source = self.script_applet_source_path(scriptname)
8890
self.install_script(source, scriptname, install_name=install_name)
8891
8892
def remove_installed_script(self, scriptname):
8893
dest = self.installed_script_path(os.path.basename(scriptname))
8894
try:
8895
os.unlink(dest)
8896
except IOError:
8897
pass
8898
except OSError:
8899
pass
8900
8901
def remove_installed_script_module(self, modulename):
8902
path = self.installed_script_module_path(modulename)
8903
os.unlink(path)
8904
8905
def remove_installed_modules(self, modulename):
8906
dest = os.path.join("scripts", "modules", modulename)
8907
try:
8908
shutil.rmtree(dest)
8909
except IOError:
8910
pass
8911
except OSError:
8912
pass
8913
8914
def get_mavlink_connection_going(self):
8915
# get a mavlink connection going
8916
try:
8917
retries = 20
8918
if self.gdb:
8919
retries = 20000
8920
self.mav = mavutil.mavlink_connection(
8921
self.autotest_connection_string_to_ardupilot(),
8922
retries=retries,
8923
robust_parsing=True,
8924
source_system=250,
8925
source_component=250,
8926
autoreconnect=True,
8927
dialect="all", # if we don't pass this in we end up with the wrong mavlink version...
8928
)
8929
except Exception as msg:
8930
self.progress("Failed to start mavlink connection on %s: %s" %
8931
(self.autotest_connection_string_to_ardupilot(), msg,))
8932
raise
8933
self.mav.message_hooks.append(self.message_hook)
8934
self.mav.mav.set_send_callback(self.send_message_hook, self)
8935
self.mav.idle_hooks.append(self.idle_hook)
8936
8937
# we need to wait for a heartbeat here. If we don't then
8938
# self.mav.target_system will be zero because it hasn't
8939
# "locked on" to a target system yet.
8940
self.wait_heartbeat()
8941
self.set_streamrate(self.sitl_streamrate())
8942
8943
def show_test_timings_key_sorter(self, t):
8944
(k, v) = t
8945
return ((v, k))
8946
8947
def show_test_timings(self):
8948
if len(self.test_timings.keys()) == 0:
8949
return
8950
longest = 0
8951
for desc in self.test_timings.keys():
8952
if len(desc) > longest:
8953
longest = len(desc)
8954
tests_total_time = 0
8955
for desc, test_time in sorted(self.test_timings.items(),
8956
key=self.show_test_timings_key_sorter):
8957
fmt = "%" + str(longest) + "s: %.2fs"
8958
tests_total_time += test_time
8959
self.progress(fmt % (desc, test_time))
8960
self.progress(fmt % ("**--tests_total_time--**", tests_total_time))
8961
self.progress("mavproxy_start was called %u times" %
8962
(self.start_mavproxy_count,))
8963
self.progress("Supplied terrain data to autopilot in %u messages" %
8964
(self.terrain_data_messages_sent,))
8965
8966
def send_statustext(self, text):
8967
if not isinstance(text, bytes):
8968
text = bytes(text, "ascii")
8969
seq = 0
8970
while len(text):
8971
self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text[:50], id=self.statustext_id, chunk_seq=seq)
8972
text = text[50:]
8973
seq += 1
8974
self.statustext_id += 1
8975
if self.statustext_id > 255:
8976
self.statustext_id = 1
8977
8978
def get_stacktrace(self):
8979
return ''.join(traceback.format_stack())
8980
8981
def get_exception_stacktrace(self, e):
8982
ret = "%s\n" % e
8983
ret += ''.join(traceback.format_exception(type(e),
8984
e,
8985
tb=e.__traceback__))
8986
return ret
8987
8988
def bin_logs(self):
8989
return glob.glob("logs/*.BIN")
8990
8991
def remove_bin_logs(self):
8992
util.run_cmd('rm -f logs/*.BIN logs/LASTLOG.TXT')
8993
8994
def remove_ardupilot_terrain_cache(self):
8995
'''removes the terrain files ArduPilot keeps in its onboiard storage'''
8996
util.run_cmd('rm -f %s' % util.reltopdir("terrain/*.DAT"))
8997
8998
def check_logs(self, name, bin_logs=None):
8999
'''called to move relevant log files from our working directory to the
9000
buildlogs directory'''
9001
if not self.move_logs_on_test_failure:
9002
return
9003
to_dir = self.logs_dir
9004
# move telemetry log files
9005
for log in glob.glob("autotest-*.tlog"):
9006
bname = os.path.basename(log)
9007
newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))
9008
print("Renaming %s to %s" % (log, newname))
9009
shutil.move(log, newname)
9010
# move binary log files
9011
if bin_logs is None:
9012
bin_logs = self.bin_logs()
9013
for log in sorted(bin_logs):
9014
bname = os.path.basename(log)
9015
newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))
9016
print("Renaming %s to %s" % (log, newname))
9017
shutil.move(log, newname)
9018
# move core files
9019
save_binaries = False
9020
corefiles = []
9021
corefiles.extend(glob.glob("core*"))
9022
corefiles.extend(glob.glob("ap-*.core"))
9023
for log in sorted(corefiles):
9024
bname = os.path.basename(log)
9025
newname = os.path.join(to_dir, "%s-%s-%s" % (bname, self.log_name(), name))
9026
print("Renaming %s to %s" % (log, newname))
9027
shutil.move(log, newname)
9028
save_binaries = True
9029
if save_binaries:
9030
util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir,
9031
directory=util.reltopdir('.'))
9032
9033
def run_one_test(self, test, interact=False, suppress_stdout=False):
9034
'''new-style run-one-test used by run_tests'''
9035
for i in range(0, test.attempts-1):
9036
result = self.run_one_test_attempt(test, interact=interact, attempt=i+2, suppress_stdout=suppress_stdout)
9037
if result.passed:
9038
return result
9039
self.progress("Run attempt failed. Retrying")
9040
return self.run_one_test_attempt(test, interact=interact, attempt=1, suppress_stdout=suppress_stdout)
9041
9042
def print_exception_caught(self, e, send_statustext=True):
9043
self.progress("Exception caught: %s" %
9044
self.get_exception_stacktrace(e))
9045
path = None
9046
try:
9047
path = self.current_onboard_log_filepath()
9048
except IndexError:
9049
pass
9050
self.progress("Most recent logfile: %s" % (path, ), send_statustext=send_statustext)
9051
9052
def progress_file_content(self, filepath):
9053
with open(filepath) as f:
9054
for line in f:
9055
self.progress(line.rstrip())
9056
9057
def dump_process_status(self, result):
9058
'''used to show where the SITL process is upto. Often caused when
9059
we've lost contact'''
9060
9061
if self.sitl.isalive():
9062
self.progress("pexpect says it is alive")
9063
for tool in "dumpstack.sh", "dumpcore.sh":
9064
tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)
9065
if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:
9066
reason = "Failed %s" % (tool,)
9067
self.progress(reason)
9068
result.reason = reason
9069
result.passed = False
9070
else:
9071
self.progress("pexpect says it is dead")
9072
9073
# try dumping the process status file for more information:
9074
status_filepath = "/proc/%u/status" % self.sitl.pid
9075
self.progress("Checking for status filepath (%s)" % status_filepath)
9076
if os.path.exists(status_filepath):
9077
self.progress_file_content(status_filepath)
9078
else:
9079
self.progress("... does not exist")
9080
9081
def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=False):
9082
'''called by run_one_test to actually run the test in a retry loop'''
9083
name = test.name
9084
desc = test.description
9085
test_function = test.function
9086
test_kwargs = test.kwargs
9087
if attempt != 1:
9088
self.progress("RETRYING %s" % name)
9089
test_output_filename = self.buildlogs_path("%s-%s-retry-%u.txt" %
9090
(self.log_name(), name, attempt-1))
9091
else:
9092
test_output_filename = self.buildlogs_path("%s-%s.txt" %
9093
(self.log_name(), name))
9094
9095
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)
9096
9097
start_message_hooks = copy.copy(self.message_hooks)
9098
9099
prettyname = "%s (%s)" % (name, desc)
9100
self.start_test(prettyname)
9101
self.set_current_test_name(name)
9102
old_contexts_length = len(self.contexts)
9103
self.context_push()
9104
9105
start_time = time.time()
9106
9107
orig_speedup = None
9108
9109
hooks_removed = False
9110
9111
ex = None
9112
try:
9113
self.check_rc_defaults()
9114
self.change_mode(self.default_mode())
9115
# ArduPilot can still move the current waypoint from 0,
9116
# even if we are not in AUTO mode, so cehck_afterwards=False:
9117
self.set_current_waypoint(0, check_afterwards=False)
9118
self.drain_mav()
9119
self.drain_all_pexpects()
9120
if test.speedup is not None:
9121
self.progress("Overriding speedup to %u" % test.speedup)
9122
orig_speedup = self.get_parameter("SIM_SPEEDUP")
9123
self.set_parameter("SIM_SPEEDUP", test.speedup)
9124
9125
test_function(**test_kwargs)
9126
except Exception as e:
9127
self.print_exception_caught(e)
9128
ex = e
9129
# reset the message hooks; we've failed-via-exception and
9130
# can't expect the hooks to have been cleaned up
9131
for h in copy.copy(self.message_hooks):
9132
if h not in start_message_hooks:
9133
self.message_hooks.remove(h)
9134
hooks_removed = True
9135
self.test_timings[desc] = time.time() - start_time
9136
reset_needed = self.contexts[-1].sitl_commandline_customised
9137
9138
if orig_speedup is not None:
9139
self.set_parameter("SIM_SPEEDUP", orig_speedup)
9140
9141
passed = True
9142
if ex is not None:
9143
passed = False
9144
9145
result = Result(test)
9146
result.time_elapsed = self.test_timings[desc]
9147
9148
ardupilot_alive = False
9149
try:
9150
self.wait_heartbeat()
9151
ardupilot_alive = True
9152
except Exception:
9153
# process is dead
9154
self.progress("No heartbeat after test", send_statustext=False)
9155
self.dump_process_status(result)
9156
9157
passed = False
9158
reset_needed = True
9159
9160
try:
9161
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
9162
except Exception as e:
9163
self.print_exception_caught(e, send_statustext=False)
9164
passed = False
9165
9166
pre_reboot_bin_logs = self.bin_logs()
9167
9168
# if we haven't already reset ArduPilot because it's dead,
9169
# then ensure the vehicle was disarmed at the end of the test.
9170
# If it wasn't then the test is considered failed:
9171
if ardupilot_alive and self.armed() and not self.is_tracker():
9172
if ex is None:
9173
ex = ArmedAtEndOfTestException("Still armed at end of test")
9174
self.progress("Armed at end of test; force-rebooting SITL")
9175
self.set_rc_default() # otherwise we might start calibrating ESCs...
9176
try:
9177
self.disarm_vehicle(force=True)
9178
except AutoTestTimeoutException:
9179
reset_needed = True
9180
self.forced_post_test_sitl_reboots += 1
9181
if reset_needed:
9182
self.progress("Force-resetting SITL")
9183
self.reset_SITL_commandline()
9184
else:
9185
self.progress("Force-rebooting SITL")
9186
self.zero_throttle()
9187
self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it
9188
passed = False
9189
elif ardupilot_alive and not passed: # implicit reboot after a failed test:
9190
self.progress("Test failed but ArduPilot process alive; rebooting")
9191
self.reboot_sitl() # that'll learn it
9192
9193
if self._mavproxy is not None:
9194
self.progress("Stopping auto-started mavproxy")
9195
if self.use_map:
9196
self.mavproxy.send("module unload map\n")
9197
self.mavproxy.expect("Unloaded module map")
9198
9199
self.expect_list_remove(self._mavproxy)
9200
util.pexpect_close(self._mavproxy)
9201
self._mavproxy = None
9202
9203
corefiles = []
9204
corefiles.extend(glob.glob("core*"))
9205
corefiles.extend(glob.glob("ap-*.core"))
9206
if corefiles:
9207
self.progress('Corefiles detected: %s' % str(corefiles))
9208
passed = False
9209
9210
if len(self.contexts) != old_contexts_length:
9211
self.progress("context count mismatch (want=%u got=%u); popping extras" %
9212
(old_contexts_length, len(self.contexts)))
9213
passed = False
9214
# pop off old contexts to clean up message hooks etc
9215
while len(self.contexts) > old_contexts_length:
9216
try:
9217
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
9218
except Exception as e:
9219
self.print_exception_caught(e, send_statustext=False)
9220
self.progress("Done popping extra contexts")
9221
9222
# make sure we don't leave around stray listeners:
9223
if len(self.message_hooks) != len(start_message_hooks):
9224
self.progress("Stray message listeners: %s vs start %s" %
9225
(str(self.message_hooks), str(start_message_hooks)))
9226
passed = False
9227
9228
if passed:
9229
# self.remove_bin_logs() # can't do this as one of the binlogs is probably open for writing by the SITL process. If we force a rotate before running tests then we can do this. # noqa
9230
pass
9231
else:
9232
if self.logs_dir is not None:
9233
# stash the binary logs and corefiles away for later analysis
9234
self.check_logs(name, bin_logs=pre_reboot_bin_logs)
9235
9236
if passed:
9237
self.progress('PASSED: "%s"' % prettyname)
9238
else:
9239
self.progress('FAILED: "%s": %s (see %s)' %
9240
(prettyname, repr(ex), test_output_filename))
9241
result.exception = ex
9242
result.debug_filename = test_output_filename
9243
if interact:
9244
self.progress("Starting MAVProxy interaction as directed")
9245
self.mavproxy.interact()
9246
9247
if self.reset_after_every_test:
9248
reset_needed = True
9249
9250
if reset_needed:
9251
self.reset_SITL_commandline()
9252
9253
if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling
9254
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
9255
self.set_current_waypoint(0, check_afterwards=False)
9256
9257
tee.close()
9258
9259
result.passed = passed
9260
return result
9261
9262
def defaults_filepath(self):
9263
return None
9264
9265
def start_mavproxy(self, sitl_rcin_port=None, master=None, options=None):
9266
self.start_mavproxy_count += 1
9267
if self.mavproxy is not None:
9268
return self.mavproxy
9269
self.progress("Starting MAVProxy")
9270
9271
# determine a good pexpect timeout for reading MAVProxy's
9272
# output; some regmes may require longer timeouts.
9273
pexpect_timeout = 60
9274
if self.valgrind or self.callgrind:
9275
pexpect_timeout *= 10
9276
9277
if sitl_rcin_port is None:
9278
sitl_rcin_port = self.sitl_rcin_port()
9279
9280
if master is None:
9281
master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762)
9282
9283
if options is None:
9284
options = self.mavproxy_options()
9285
else:
9286
op = self.mavproxy_options().copy()
9287
op.extend(options)
9288
options = op
9289
9290
mavproxy = util.start_MAVProxy_SITL(
9291
self.vehicleinfo_key(),
9292
master=master,
9293
logfile=self.mavproxy_logfile,
9294
options=options,
9295
pexpect_timeout=pexpect_timeout,
9296
sitl_rcin_port=sitl_rcin_port,
9297
)
9298
mavproxy.expect(r'Telemetry log: (\S+)\r\n')
9299
self.logfile = mavproxy.match.group(1)
9300
self.progress("LOGFILE %s" % self.logfile)
9301
self.try_symlink_tlog()
9302
9303
self.expect_list_add(mavproxy)
9304
util.expect_setup_callback(mavproxy, self.expect_callback)
9305
self._mavproxy = mavproxy # so we can clean up after tests....
9306
return mavproxy
9307
9308
def stop_mavproxy(self, mavproxy):
9309
if self.mavproxy is not None:
9310
return
9311
self.progress("Stopping MAVProxy")
9312
self.expect_list_remove(mavproxy)
9313
util.pexpect_close(mavproxy)
9314
self._mavproxy = None
9315
9316
def start_SITL(self, binary=None, sitl_home=None, **sitl_args):
9317
if sitl_home is None:
9318
sitl_home = self.sitl_home()
9319
start_sitl_args = {
9320
"breakpoints": self.breakpoints,
9321
"disable_breakpoints": self.disable_breakpoints,
9322
"gdb": self.gdb,
9323
"gdb_no_tui": self.gdb_no_tui,
9324
"gdbserver": self.gdbserver,
9325
"lldb": self.lldb,
9326
"strace": self.strace,
9327
"home": sitl_home,
9328
"speedup": self.speedup,
9329
"valgrind": self.valgrind,
9330
"callgrind": self.callgrind,
9331
"wipe": True,
9332
"enable_fgview": self.enable_fgview,
9333
}
9334
start_sitl_args.update(**sitl_args)
9335
if ("defaults_filepath" not in start_sitl_args or
9336
start_sitl_args["defaults_filepath"] is None):
9337
start_sitl_args["defaults_filepath"] = self.defaults_filepath()
9338
9339
if "model" not in start_sitl_args or start_sitl_args["model"] is None:
9340
start_sitl_args["model"] = self.frame
9341
self.progress("Starting SITL", send_statustext=False)
9342
if binary is None:
9343
binary = self.binary
9344
self.sitl = util.start_SITL(binary, **start_sitl_args)
9345
self.expect_list_add(self.sitl)
9346
self.sup_prog = []
9347
count = 0
9348
for sup_binary in self.sup_binaries:
9349
self.progress("Starting Supplementary Program ", sup_binary)
9350
start_sitl_args["customisations"] = [sup_binary['customisation']]
9351
start_sitl_args["supplementary"] = True
9352
start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count)
9353
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
9354
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
9355
self.sup_prog.append(sup_prog_link)
9356
self.expect_list_add(sup_prog_link)
9357
count += 1
9358
9359
# mavlink will have disconnected here. Explicitly reconnect,
9360
# or the first packet we send will be lost:
9361
if self.mav is not None:
9362
self.mav.reconnect()
9363
9364
def get_supplementary_programs(self):
9365
return self.sup_prog
9366
9367
def stop_sup_program(self, instance=None):
9368
self.progress("Stopping supplementary program")
9369
if instance is None:
9370
# close all sup programs
9371
for prog in self.sup_prog:
9372
self.expect_list_remove(prog)
9373
self.sup_prog.remove(prog)
9374
util.pexpect_close(prog)
9375
else:
9376
# close only the instance passed
9377
prog = self.sup_prog[instance]
9378
self.expect_list_remove(prog)
9379
self.sup_prog[instance] = None
9380
util.pexpect_close(prog)
9381
9382
def start_sup_program(self, instance=None, args=None):
9383
self.progress("Starting supplementary program")
9384
start_sitl_args = {
9385
"breakpoints": self.breakpoints,
9386
"disable_breakpoints": self.disable_breakpoints,
9387
"gdb": self.gdb,
9388
"gdb_no_tui": self.gdb_no_tui,
9389
"gdbserver": self.gdbserver,
9390
"lldb": self.lldb,
9391
"strace": self.strace,
9392
"home": self.sitl_home(),
9393
"speedup": self.speedup,
9394
"valgrind": self.valgrind,
9395
"callgrind": self.callgrind,
9396
"wipe": True,
9397
}
9398
for i in range(len(self.sup_binaries)):
9399
if instance is not None and instance != i:
9400
continue
9401
sup_binary = self.sup_binaries[i]
9402
start_sitl_args["customisations"] = [sup_binary['customisation']]
9403
if args is not None:
9404
start_sitl_args["customisations"] = [sup_binary['customisation'], args]
9405
start_sitl_args["supplementary"] = True
9406
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
9407
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
9408
time.sleep(1)
9409
self.sup_prog[i] = sup_prog_link # add to list
9410
self.expect_list_add(sup_prog_link) # add to expect list
9411
9412
def sitl_is_running(self):
9413
if self.sitl is None:
9414
return False
9415
return self.sitl.isalive()
9416
9417
def autostart_mavproxy(self):
9418
return self.use_map
9419
9420
def init(self):
9421
"""Initialize autotest feature."""
9422
self.mavproxy_logfile = self.open_mavproxy_logfile()
9423
9424
if self.frame is None:
9425
self.frame = self.default_frame()
9426
9427
if self.frame is None:
9428
raise ValueError("frame must not be None")
9429
9430
self.progress("Starting simulator")
9431
self.start_SITL()
9432
9433
os.environ['MAVLINK20'] = '1'
9434
9435
self.progress("Starting MAVLink connection")
9436
self.get_mavlink_connection_going()
9437
9438
if self.autostart_mavproxy():
9439
self.mavproxy = self.start_mavproxy()
9440
9441
self.expect_list_clear()
9442
self.expect_list_extend([self.sitl, self.mavproxy])
9443
self.expect_list_extend(self.sup_prog)
9444
9445
# need to wait for a heartbeat to arrive as then mavutil will
9446
# select the correct set of messages for us to receive in
9447
# self.mav.messages. You can actually receive messages with
9448
# recv_match and those will not be in self.mav.messages until
9449
# you do this!
9450
self.wait_heartbeat()
9451
self.get_autopilot_firmware_version()
9452
self.progress("Sim time: %f" % (self.get_sim_time(),))
9453
self.apply_default_parameters()
9454
9455
if not self.sitl_is_running():
9456
# we run this just to make sure exceptions are likely to
9457
# work OK.
9458
raise NotAchievedException("SITL is not running")
9459
self.progress("SITL is running")
9460
9461
self.progress("Ready to start testing!")
9462
9463
def upload_using_mission_protocol(self, mission_type, items):
9464
'''mavlink2 required'''
9465
target_system = 1
9466
target_component = 1
9467
self.do_timesync_roundtrip()
9468
tstart = self.get_sim_time()
9469
self.mav.mav.mission_count_send(target_system,
9470
target_component,
9471
len(items),
9472
mission_type)
9473
remaining_to_send = set(range(0, len(items)))
9474
sent = set()
9475
timeout = (10 + len(items)/10.0)
9476
while True:
9477
if self.get_sim_time_cached() - tstart > timeout:
9478
raise NotAchievedException("timeout uploading %s" % str(mission_type))
9479
if len(remaining_to_send) == 0:
9480
self.progress("All sent")
9481
break
9482
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],
9483
blocking=True,
9484
timeout=1)
9485
if m is None:
9486
continue
9487
9488
if m.get_type() == 'MISSION_ACK':
9489
if (m.target_system == 255 and
9490
m.target_component == 0 and
9491
m.type == 1 and
9492
m.mission_type == 0):
9493
# this is just MAVProxy trying to screw us up
9494
continue
9495
raise NotAchievedException(f"Received unexpected mission ack {self.dump_message_verbose(m)}")
9496
9497
self.progress("Handling request for item %u/%u" % (m.seq, len(items)-1))
9498
self.progress("Item (%s)" % str(items[m.seq]))
9499
if m.seq in sent:
9500
self.progress("received duplicate request for item %u" % m.seq)
9501
continue
9502
9503
if m.seq not in remaining_to_send:
9504
raise NotAchievedException("received request for unknown item %u" % m.seq)
9505
9506
if m.mission_type != mission_type:
9507
raise NotAchievedException("received request for item from wrong mission type")
9508
9509
if items[m.seq].mission_type != mission_type:
9510
raise NotAchievedException(f"supplied item not of correct mission type (want={mission_type} got={items[m.seq].mission_type}") # noqa:501
9511
if items[m.seq].target_system != target_system:
9512
raise NotAchievedException("supplied item not of correct target system")
9513
if items[m.seq].target_component != target_component:
9514
raise NotAchievedException("supplied item not of correct target component")
9515
if items[m.seq].seq != m.seq:
9516
raise NotAchievedException("supplied item has incorrect sequence number (%u vs %u)" %
9517
(items[m.seq].seq, m.seq))
9518
9519
items[m.seq].pack(self.mav.mav)
9520
self.mav.mav.send(items[m.seq])
9521
remaining_to_send.discard(m.seq)
9522
sent.add(m.seq)
9523
9524
timeout += 10 # we received a good request for item; be generous with our timeouts
9525
9526
m = self.assert_receive_message('MISSION_ACK')
9527
if m.mission_type != mission_type:
9528
raise NotAchievedException("Mission ack not of expected mission type")
9529
if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:
9530
raise NotAchievedException("Mission upload failed (%s)" %
9531
(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),)
9532
self.progress("Upload of all %u items succeeded" % len(items))
9533
9534
def assert_fetch_mission_item_int(self, target_system, target_component, seq, mission_type):
9535
self.mav.mav.mission_request_int_send(target_system,
9536
target_component,
9537
seq,
9538
mission_type)
9539
m = self.assert_receive_message(
9540
'MISSION_ITEM_INT',
9541
condition=f'MISSION_ITEM_INT.mission_type=={mission_type}',
9542
)
9543
if m is None:
9544
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
9545
return m
9546
9547
def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10):
9548
'''mavlink2 required'''
9549
target_system = 1
9550
target_component = 1
9551
self.progress("Sending mission_request_list")
9552
tstart = self.get_sim_time()
9553
self.mav.mav.mission_request_list_send(target_system,
9554
target_component,
9555
mission_type)
9556
9557
while True:
9558
if self.get_sim_time_cached() - tstart > timeout:
9559
raise NotAchievedException("Did not get MISSION_COUNT packet")
9560
m = self.mav.recv_match(blocking=True, timeout=0.1)
9561
if m is None:
9562
raise NotAchievedException("Did not get MISSION_COUNT response")
9563
if verbose:
9564
self.progress(str(m))
9565
if m.get_type() == 'MISSION_ACK':
9566
if m.target_system == 255 and m.target_component == 0:
9567
# this was for MAVProxy
9568
continue
9569
self.progress(self.dump_message_verbose(m))
9570
raise NotAchievedException("Received MISSION_ACK while waiting for MISSION_COUNT")
9571
if m.get_type() != 'MISSION_COUNT':
9572
continue
9573
if m.target_component != self.mav.source_system:
9574
continue
9575
if m.mission_type != mission_type:
9576
raise NotAchievedException("Mission count response of incorrect type")
9577
break
9578
9579
items = []
9580
tstart = self.get_sim_time_cached()
9581
remaining_to_receive = set(range(0, m.count))
9582
next_to_request = 0
9583
timeout = m.count
9584
timeout *= self.speedup / 10.0
9585
timeout += 10
9586
while True:
9587
delta_t = self.get_sim_time_cached() - tstart
9588
if delta_t > timeout:
9589
raise NotAchievedException(
9590
"timeout downloading type=%s after %s seconds of %s allowed" %
9591
(mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name,
9592
delta_t, timeout))
9593
if len(remaining_to_receive) == 0:
9594
self.progress("All received")
9595
return items
9596
self.progress("Requesting item %u (remaining=%u)" %
9597
(next_to_request, len(remaining_to_receive)))
9598
m = self.assert_fetch_mission_item_int(target_system, target_component, next_to_request, mission_type)
9599
if m.target_system != self.mav.source_system:
9600
raise NotAchievedException("Wrong target system (want=%u got=%u)" %
9601
(self.mav.source_system, m.target_system))
9602
if m.target_component != self.mav.source_component:
9603
raise NotAchievedException("Wrong target component")
9604
self.progress("Got (%s)" % str(m))
9605
if m.mission_type != mission_type:
9606
raise NotAchievedException("Received waypoint of wrong type")
9607
if m.seq != next_to_request:
9608
raise NotAchievedException("Received waypoint is out of sequence")
9609
self.progress("Item %u OK" % m.seq)
9610
timeout += 10 # we received an item; be generous with our timeouts
9611
items.append(m)
9612
next_to_request += 1
9613
remaining_to_receive.discard(m.seq)
9614
9615
def dump_message_verbose(self, m):
9616
'''return verbose dump of m. Wraps the pymavlink routine which
9617
inconveniently takes a filehandle'''
9618
f = io.StringIO()
9619
mavutil.dump_message_verbose(f, m)
9620
return f.getvalue()
9621
9622
def poll_home_position(self, quiet=True, timeout=30):
9623
old = self.mav.messages.get("HOME_POSITION", None)
9624
tstart = self.get_sim_time()
9625
while True:
9626
if self.get_sim_time_cached() - tstart > timeout:
9627
raise NotAchievedException("Failed to poll home position")
9628
if not quiet:
9629
self.progress("Sending MAV_CMD_GET_HOME_POSITION")
9630
try:
9631
self.run_cmd(
9632
mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
9633
quiet=quiet,
9634
)
9635
except ValueError:
9636
continue
9637
m = self.mav.messages.get("HOME_POSITION", None)
9638
if m is None:
9639
continue
9640
if old is None:
9641
break
9642
if m._timestamp != old._timestamp:
9643
break
9644
self.progress("Polled home position (%s)" % str(m))
9645
return m
9646
9647
def position_target_loc(self):
9648
'''returns target location based on POSITION_TARGET_GLOBAL_INT'''
9649
m = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)
9650
return mavutil.location(m.lat_int*1e-7, m.lon_int*1e-7, m.alt)
9651
9652
def current_waypoint(self):
9653
m = self.assert_receive_message('MISSION_CURRENT')
9654
return m.seq
9655
9656
def distance_to_nav_target(self, use_cached_nav_controller_output=False):
9657
'''returns distance to waypoint navigation target in metres'''
9658
m = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None)
9659
if m is None or not use_cached_nav_controller_output:
9660
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=10)
9661
return m.wp_dist
9662
9663
def distance_to_home(self, use_cached_home=False):
9664
m = self.mav.messages.get("HOME_POSITION", None)
9665
if use_cached_home is False or m is None:
9666
m = self.poll_home_position(quiet=True)
9667
here = self.assert_receive_message('GLOBAL_POSITION_INT')
9668
return self.get_distance_int(m, here)
9669
9670
def home_position_as_mav_location(self):
9671
m = self.poll_home_position()
9672
return mavutil.location(m.latitude*1.0e-7, m.longitude*1.0e-7, m.altitude*1.0e-3, 0)
9673
9674
def offset_location_ne(self, location, metres_north, metres_east):
9675
'''return a new location offset from passed-in location'''
9676
(target_lat, target_lng) = mavextra.gps_offset(location.lat,
9677
location.lng,
9678
metres_east,
9679
metres_north)
9680
return mavutil.location(target_lat,
9681
target_lng,
9682
location.alt,
9683
location.heading)
9684
9685
def offset_location_heading_distance(self, location, bearing, distance):
9686
(target_lat, target_lng) = mavextra.gps_newpos(
9687
location.lat,
9688
location.lng,
9689
bearing,
9690
distance
9691
)
9692
return mavutil.location(
9693
target_lat,
9694
target_lng,
9695
location.alt,
9696
location.heading
9697
)
9698
9699
def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):
9700
tstart = self.get_sim_time()
9701
while True:
9702
if self.get_sim_time_cached() - tstart > timeout:
9703
break
9704
m = self.assert_receive_message('VFR_HUD', timeout=timeout)
9705
if m.groundspeed > want+tolerance:
9706
raise NotAchievedException("Too fast (%f > %f)" %
9707
(m.groundspeed, want))
9708
if m.groundspeed < want-tolerance:
9709
raise NotAchievedException("Too slow (%f < %f)" %
9710
(m.groundspeed, want))
9711
self.progress("GroundSpeed OK (got=%f) (want=%f)" %
9712
(m.groundspeed, want))
9713
9714
def set_home(self, loc):
9715
'''set home to supplied loc'''
9716
self.run_cmd_int(
9717
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9718
p5=int(loc.lat*1e7),
9719
p6=int(loc.lng*1e7),
9720
p7=loc.alt,
9721
)
9722
9723
def SetHome(self):
9724
'''Setting and fetching of home'''
9725
if self.is_tracker():
9726
# tracker starts armed...
9727
self.disarm_vehicle(force=True)
9728
self.reboot_sitl()
9729
9730
# HOME_POSITION is used as a surrogate for origin until we
9731
# start emitting GPS_GLOBAL_ORIGIN
9732
self.wait_ekf_happy()
9733
orig_home = self.poll_home_position()
9734
if orig_home is None:
9735
raise AutoTestTimeoutException()
9736
self.progress("Original home: %s" % str(orig_home))
9737
# original home should be close to SITL home...
9738
start_loc = self.sitl_start_location()
9739
self.progress("SITL start loc: %s" % str(start_loc))
9740
delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)
9741
if delta > 0.000006:
9742
raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %
9743
(orig_home.latitude * 1.0e-7, start_loc.lat, delta))
9744
delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)
9745
if delta > 0.000006:
9746
raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %
9747
(orig_home.longitude * 1.0e-7, start_loc.lng, delta))
9748
if self.is_rover():
9749
self.progress("### Rover skipping altitude check unti position fixes in")
9750
else:
9751
home_alt_m = orig_home.altitude * 1.0e-3
9752
if abs(home_alt_m - start_loc.alt) > 2: # metres
9753
raise ValueError("homes differ in alt got=%fm want=%fm" %
9754
(home_alt_m, start_loc.alt))
9755
new_x = orig_home.latitude + 1000
9756
new_y = orig_home.longitude + 2000
9757
new_z = orig_home.altitude + 300000 # 300 metres
9758
print("new home: %s %s %s" % (str(new_x), str(new_y), str(new_z)))
9759
self.run_cmd_int(
9760
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9761
p5=new_x,
9762
p6=new_y,
9763
p7=new_z/1000.0, # mm => m
9764
)
9765
9766
home = self.poll_home_position()
9767
self.progress("home: %s" % str(home))
9768
got_home_latitude = home.latitude
9769
got_home_longitude = home.longitude
9770
got_home_altitude = home.altitude
9771
if (got_home_latitude != new_x or
9772
got_home_longitude != new_y or
9773
abs(got_home_altitude - new_z) > 100): # float-conversion issues
9774
self.reboot_sitl()
9775
raise NotAchievedException(
9776
"Home mismatch got=(%f, %f, %f) set=(%f, %f, %f)" %
9777
(got_home_latitude, got_home_longitude, got_home_altitude,
9778
new_x, new_y, new_z))
9779
9780
self.progress("monitoring home to ensure it doesn't drift at all")
9781
tstart = self.get_sim_time()
9782
while self.get_sim_time_cached() - tstart < 10:
9783
home = self.poll_home_position(quiet=True)
9784
self.progress("home: %s" % str(home))
9785
if (home.latitude != got_home_latitude or
9786
home.longitude != got_home_longitude or
9787
home.altitude != got_home_altitude): # float-conversion issues
9788
self.reboot_sitl()
9789
raise NotAchievedException("home is drifting")
9790
9791
self.progress("Waiting for EKF to start")
9792
self.wait_ready_to_arm()
9793
self.progress("now use lat=0, lon=0 to reset home to current location")
9794
self.run_cmd_int(
9795
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9796
p5=0, # lat
9797
p6=0, # lon
9798
p7=new_z/1000.0, # mm => m
9799
)
9800
home = self.poll_home_position()
9801
self.progress("home: %s" % str(home))
9802
if self.distance_to_home(use_cached_home=True) > 1:
9803
raise NotAchievedException("Setting home to current location did not work")
9804
9805
self.progress("Setting home elsewhere again")
9806
self.run_cmd_int(
9807
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9808
p5=new_x,
9809
p6=new_y,
9810
p7=new_z/1000.0, # mm => m
9811
)
9812
if self.distance_to_home() < 10:
9813
raise NotAchievedException("Setting home to location did not work")
9814
9815
self.progress("use param1=1 to reset home to current location")
9816
self.run_cmd_int(
9817
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9818
p1=1, # use current location
9819
p5=37, # lat
9820
p6=21, # lon
9821
p7=new_z/1000.0, # mm => m
9822
)
9823
home = self.poll_home_position()
9824
self.progress("home: %s" % str(home))
9825
if self.distance_to_home() > 1:
9826
raise NotAchievedException("Setting home to current location did not work")
9827
9828
if self.is_tracker():
9829
# tracker starts armed...
9830
self.disarm_vehicle(force=True)
9831
self.reboot_sitl()
9832
9833
def zero_mag_offset_parameters(self, compass_count=3):
9834
self.progress("Zeroing Mag OFS parameters")
9835
self.get_sim_time()
9836
zero_offset_parameters_hash = {}
9837
for num in "", "2", "3":
9838
for axis in "X", "Y", "Z":
9839
name = "COMPASS_OFS%s_%s" % (num, axis)
9840
zero_offset_parameters_hash[name] = 0
9841
self.set_parameters(zero_offset_parameters_hash)
9842
# force-save the calibration values:
9843
self.run_cmd_int(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, p2=76)
9844
self.progress("zeroed mag parameters")
9845
9846
params = [
9847
[("SIM_MAG1_OFS1_X", "COMPASS_OFS_X", 0),
9848
("SIM_MAG1_OFS1_Y", "COMPASS_OFS_Y", 0),
9849
("SIM_MAG1_OFS1_Z", "COMPASS_OFS_Z", 0), ],
9850
]
9851
for count in range(2, compass_count + 1):
9852
params += [
9853
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, 0),
9854
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, 0),
9855
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, 0), ],
9856
]
9857
self.check_zero_mag_parameters(params)
9858
9859
def forty_two_mag_dia_odi_parameters(self, compass_count=3):
9860
self.progress("Forty twoing Mag DIA and ODI parameters")
9861
self.get_sim_time()
9862
params = [
9863
[("SIM_MAG1_DIA_X", "COMPASS_DIA_X", 42.0),
9864
("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", 42.0),
9865
("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", 42.0),
9866
("SIM_MAG1_ODI_X", "COMPASS_ODI_X", 42.0),
9867
("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", 42.0),
9868
("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", 42.0), ],
9869
]
9870
for count in range(2, compass_count + 1):
9871
params += [
9872
[("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, 42.0),
9873
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, 42.0),
9874
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, 42.0),
9875
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, 42.0),
9876
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, 42.0),
9877
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, 42.0), ],
9878
]
9879
self.wait_heartbeat()
9880
to_set = {}
9881
for param_set in params:
9882
for param in param_set:
9883
(_, _out, value) = param
9884
to_set[_out] = value
9885
self.set_parameters(to_set)
9886
self.check_zero_mag_parameters(params)
9887
9888
def check_mag_parameters(self, parameter_stuff, compass_number):
9889
self.progress("Checking that Mag parameter")
9890
for idx in range(0, compass_number, 1):
9891
for param in parameter_stuff[idx]:
9892
(_in, _out, value) = param
9893
got_value = self.get_parameter(_out)
9894
if abs(got_value - value) > abs(value) * 0.15:
9895
raise NotAchievedException("%s/%s not within 15%%; got %f want=%f" % (_in, _out, got_value, value))
9896
9897
def check_zero_mag_parameters(self, parameter_stuff):
9898
self.progress("Checking that Mag OFS are zero")
9899
for param_set in parameter_stuff:
9900
for param in param_set:
9901
(_in, _out, _) = param
9902
got_value = self.get_parameter(_out)
9903
max = 0.15
9904
if "DIA" in _out or "ODI" in _out:
9905
max += 42.0
9906
if abs(got_value) > max:
9907
raise NotAchievedException(
9908
"%s/%s not within 15%%; got %f want=%f" %
9909
(_in, _out, got_value, 0.0 if max > 1 else 42.0))
9910
9911
def check_zeros_mag_orient(self, compass_count=3):
9912
self.progress("zeroed mag parameters")
9913
self.verify_parameter_values({"COMPASS_ORIENT": 0})
9914
for count in range(2, compass_count + 1):
9915
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0})
9916
9917
# this autotest appears to interfere with FixedYawCalibration, no idea why.
9918
def SITLCompassCalibration(self, compass_count=3, timeout=1000):
9919
'''Test Fixed Yaw Calibration"'''
9920
9921
timeout /= 8
9922
timeout *= self.speedup
9923
9924
def reset_pos_and_start_magcal(mavproxy, tmask):
9925
mavproxy.send("sitl_stop\n")
9926
mavproxy.send("sitl_attitude 0 0 0\n")
9927
self.get_sim_time()
9928
self.run_cmd(
9929
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
9930
p1=tmask, # p1: mag_mask
9931
p2=0, # retry
9932
p3=0, # autosave
9933
p4=0, # delay
9934
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
9935
timeout=20,
9936
)
9937
mavproxy.send("sitl_magcal\n")
9938
9939
def do_prep_mag_cal_test(mavproxy, params):
9940
self.progress("Preparing the vehicle for magcal")
9941
MAG_OFS = 100
9942
MAG_DIA = 1.0
9943
MAG_ODI = 0.004
9944
params += [
9945
[("SIM_MAG1_OFS_X", "COMPASS_OFS_X", MAG_OFS),
9946
("SIM_MAG1_OFS_Y", "COMPASS_OFS_Y", MAG_OFS + 100),
9947
("SIM_MAG1_OFS_Z", "COMPASS_OFS_Z", MAG_OFS + 200),
9948
("SIM_MAG1_DIA_X", "COMPASS_DIA_X", MAG_DIA),
9949
("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", MAG_DIA + 0.1),
9950
("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", MAG_DIA + 0.2),
9951
("SIM_MAG1_ODI_X", "COMPASS_ODI_X", MAG_ODI),
9952
("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", MAG_ODI + 0.001),
9953
("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", MAG_ODI + 0.001), ],
9954
]
9955
for count in range(2, compass_count + 1):
9956
params += [
9957
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),
9958
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),
9959
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),
9960
("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),
9961
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),
9962
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),
9963
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),
9964
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),
9965
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],
9966
]
9967
self.progress("Setting calibration mode")
9968
self.wait_heartbeat()
9969
self.customise_SITL_commandline(["-M", "calibration"])
9970
self.mavproxy_load_module(mavproxy, "sitl_calibration")
9971
self.mavproxy_load_module(mavproxy, "calibration")
9972
self.mavproxy_load_module(mavproxy, "relay")
9973
self.wait_statustext("is using GPS", timeout=60)
9974
mavproxy.send("accelcalsimple\n")
9975
mavproxy.expect("Calibrated")
9976
# disable it to not interfert with calibration acceptation
9977
self.mavproxy_unload_module(mavproxy, "calibration")
9978
if self.is_copter():
9979
# set frame class to pass arming check on copter
9980
self.set_parameter("FRAME_CLASS", 1)
9981
self.progress("Setting SITL Magnetometer model value")
9982
self.set_parameter("COMPASS_AUTO_ROT", 0)
9983
# MAG_ORIENT = 4
9984
# self.set_parameter("SIM_MAG1_ORIENT", MAG_ORIENT)
9985
# for count in range(2, compass_count + 1):
9986
# self.set_parameter("SIM_MAG%d_ORIENT" % count, MAG_ORIENT * (count % 41))
9987
# # set compass external to check that orientation is found and auto set
9988
# self.set_parameter("COMPASS_EXTERN%d" % count, 1)
9989
to_set = {}
9990
for param_set in params:
9991
for param in param_set:
9992
(_in, _out, value) = param
9993
to_set[_in] = value
9994
to_set[_out] = value
9995
self.set_parameters(to_set)
9996
self.start_subtest("Zeroing Mag OFS parameters with Mavlink")
9997
self.zero_mag_offset_parameters()
9998
self.progress("=========================================")
9999
# Change the default value to unexpected 42
10000
self.forty_two_mag_dia_odi_parameters()
10001
self.progress("Zeroing Mags orientations")
10002
self.set_parameter("COMPASS_ORIENT", 0)
10003
for count in range(2, compass_count + 1):
10004
self.set_parameter("COMPASS_ORIENT%d" % count, 0)
10005
10006
# Only care about compass prearm
10007
self.set_parameter("ARMING_SKIPCHK", ~(1 << 2))
10008
10009
#################################################
10010
def do_test_mag_cal(mavproxy, params, compass_tnumber):
10011
self.start_subtest("Try magcal and make it stop around 30%")
10012
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
10013
reset_pos_and_start_magcal(mavproxy, target_mask)
10014
tstart = self.get_sim_time()
10015
reached_pct = [0] * compass_tnumber
10016
tstop = None
10017
while True:
10018
if self.get_sim_time_cached() - tstart > timeout:
10019
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
10020
m = self.mav.recv_match(type='MAG_CAL_PROGRESS', blocking=True, timeout=5)
10021
if m is None:
10022
if tstop is not None:
10023
# wait 3 second to unsure that the calibration is well stopped
10024
if self.get_sim_time_cached() - tstop > 10:
10025
if reached_pct[0] > 33:
10026
raise NotAchievedException("Mag calibration didn't stop")
10027
else:
10028
break
10029
else:
10030
continue
10031
else:
10032
continue
10033
if m is not None:
10034
self.progress("Mag CAL progress: %s" % str(m))
10035
cid = m.compass_id
10036
new_pct = int(m.completion_pct)
10037
if new_pct != reached_pct[cid]:
10038
if new_pct < reached_pct[cid]:
10039
raise NotAchievedException("Mag calibration restart when it shouldn't")
10040
reached_pct[cid] = new_pct
10041
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
10042
if cid == 0 and 13 <= reached_pct[0] <= 15:
10043
self.progress("Request again to start calibration, it shouldn't restart from 0")
10044
self.run_cmd(
10045
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
10046
p1=target_mask,
10047
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
10048
timeout=20,
10049
)
10050
10051
if reached_pct[0] > 30:
10052
self.run_cmd(
10053
mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,
10054
p1=target_mask,
10055
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
10056
)
10057
if tstop is None:
10058
tstop = self.get_sim_time_cached()
10059
if tstop is not None:
10060
# wait 3 second to unsure that the calibration is well stopped
10061
if self.get_sim_time_cached() - tstop > 3:
10062
raise NotAchievedException("Mag calibration didn't stop")
10063
self.check_zero_mag_parameters(params)
10064
self.check_zeros_mag_orient()
10065
10066
#################################################
10067
self.start_subtest("Try magcal and make it failed")
10068
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
10069
old_cal_fit = self.get_parameter("COMPASS_CAL_FIT")
10070
self.set_parameter("COMPASS_CAL_FIT", 0.001, add_to_context=False)
10071
reset_pos_and_start_magcal(mavproxy, target_mask)
10072
tstart = self.get_sim_time()
10073
reached_pct = [0] * compass_tnumber
10074
report_get = [0] * compass_tnumber
10075
while True:
10076
if self.get_sim_time_cached() - tstart > timeout:
10077
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
10078
m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=10)
10079
if m.get_type() == "MAG_CAL_REPORT":
10080
if report_get[m.compass_id] == 0:
10081
self.progress("Report: %s" % str(m))
10082
if m.cal_status == mavutil.mavlink.MAG_CAL_FAILED:
10083
report_get[m.compass_id] = 1
10084
else:
10085
raise NotAchievedException("Mag calibration didn't failed")
10086
if all(ele >= 1 for ele in report_get):
10087
self.progress("All Mag report failure")
10088
break
10089
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
10090
self.progress("Mag CAL progress: %s" % str(m))
10091
cid = m.compass_id
10092
new_pct = int(m.completion_pct)
10093
if new_pct != reached_pct[cid]:
10094
reached_pct[cid] = new_pct
10095
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
10096
if cid == 0 and 49 <= reached_pct[0] <= 50:
10097
self.progress("Try arming during calibration, should failed")
10098
self.try_arm(False, "Compass calibration running")
10099
10100
self.check_zero_mag_parameters(params)
10101
self.check_zeros_mag_orient()
10102
self.set_parameter("COMPASS_CAL_FIT", old_cal_fit, add_to_context=False)
10103
10104
#################################################
10105
self.start_subtest("Try magcal and wait success")
10106
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
10107
reset_pos_and_start_magcal(mavproxy, target_mask)
10108
progress_count = [0] * compass_tnumber
10109
reached_pct = [0] * compass_tnumber
10110
report_get = [0] * compass_tnumber
10111
tstart = self.get_sim_time()
10112
while True:
10113
if self.get_sim_time_cached() - tstart > timeout:
10114
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
10115
m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=5)
10116
if m.get_type() == "MAG_CAL_REPORT":
10117
if report_get[m.compass_id] == 0:
10118
self.progress("Report: %s" % self.dump_message_verbose(m))
10119
param_names = ["SIM_MAG1_ORIENT"]
10120
for i in range(2, compass_tnumber+1):
10121
param_names.append("SIM_MAG%u_ORIENT" % i)
10122
for param_name in param_names:
10123
self.progress("%s=%f" % (param_name, self.get_parameter(param_name)))
10124
if m.cal_status == mavutil.mavlink.MAG_CAL_SUCCESS:
10125
threshold = 95
10126
if reached_pct[m.compass_id] < threshold:
10127
raise NotAchievedException(
10128
"Mag calibration report SUCCESS without >=%f%% completion (got %f%%)" %
10129
(threshold, reached_pct[m.compass_id]))
10130
report_get[m.compass_id] = 1
10131
else:
10132
raise NotAchievedException(
10133
"Mag calibration didn't SUCCEED (cal_status=%u) (progress_count=%s)" %
10134
(m.cal_status, progress_count[m.compass_id],))
10135
if all(ele >= 1 for ele in report_get):
10136
self.progress("All Mag report SUCCESS")
10137
break
10138
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
10139
cid = m.compass_id
10140
new_pct = int(m.completion_pct)
10141
progress_count[cid] += 1
10142
if new_pct != reached_pct[cid]:
10143
reached_pct[cid] = new_pct
10144
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
10145
mavproxy.send("sitl_stop\n")
10146
mavproxy.send("sitl_attitude 0 0 0\n")
10147
self.progress("Checking that value aren't changed without acceptation")
10148
self.check_zero_mag_parameters(params)
10149
self.check_zeros_mag_orient()
10150
self.progress("Send acceptation and check value")
10151
self.wait_heartbeat()
10152
self.run_cmd(
10153
mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,
10154
p1=target_mask, # p1: mag_mask
10155
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
10156
timeout=20,
10157
)
10158
self.check_mag_parameters(params, compass_tnumber)
10159
self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG1_ORIENT")})
10160
for count in range(2, compass_tnumber + 1):
10161
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})
10162
self.try_arm(False, "Compass calibrated requires reboot")
10163
10164
# test buzzer/notify ?
10165
self.progress("Rebooting and making sure we could arm with these values")
10166
self.drain_mav()
10167
self.reboot_sitl()
10168
if False: # FIXME! This fails with compasses inconsistent!
10169
self.wait_ready_to_arm(timeout=60)
10170
self.progress("Setting manually the parameter for other sensor to avoid compass consistency error")
10171
for idx in range(compass_tnumber, compass_count, 1):
10172
for param in params[idx]:
10173
(_in, _out, value) = param
10174
self.set_parameter(_out, value)
10175
for count in range(compass_tnumber + 1, compass_count + 1):
10176
self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))
10177
self.arm_vehicle()
10178
self.progress("Test calibration rejection when armed")
10179
self.run_cmd(
10180
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
10181
p1=target_mask, # p1: mag_mask
10182
p2=0, # retry
10183
p3=0, # autosave
10184
p4=0, # delay
10185
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
10186
timeout=20,
10187
)
10188
self.disarm_vehicle()
10189
self.mavproxy_unload_module(mavproxy, "relay")
10190
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
10191
10192
ex = None
10193
10194
mavproxy = self.start_mavproxy()
10195
try:
10196
self.set_parameter("AHRS_EKF_TYPE", 10)
10197
self.set_parameter("SIM_GND_BEHAV", 0)
10198
10199
curr_params = []
10200
target_mask = 0
10201
# we test all bitmask plus 0 for all
10202
for run in range(-1, compass_count, 1):
10203
ntest_compass = compass_count
10204
if run < 0:
10205
# use bitmask 0 for all compass
10206
target_mask = 0
10207
else:
10208
target_mask |= (1 << run)
10209
ntest_compass = run + 1
10210
do_prep_mag_cal_test(mavproxy, curr_params)
10211
do_test_mag_cal(mavproxy, curr_params, ntest_compass)
10212
10213
except Exception as e:
10214
self.progress("Caught exception: %s" %
10215
self.get_exception_stacktrace(e))
10216
ex = e
10217
self.mavproxy_unload_module(mavproxy, "relay")
10218
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
10219
if ex is not None:
10220
raise ex
10221
10222
self.stop_mavproxy(mavproxy)
10223
10224
# need to reboot SITL after moving away from EKF type 10; we
10225
# can end up with home set but origin not and that will lead
10226
# to bad things.
10227
self.reboot_sitl()
10228
10229
def test_mag_reordering_assert_mag_transform(self, values, transforms):
10230
'''transforms ought to be read as, "take all the parameter values from
10231
the first compass parameters and shove them into the second indicating
10232
compass parameters'''
10233
10234
# create a set of mappings from one parameter name to another
10235
# e.g. COMPASS_OFS_X => COMPASS_OFS2_X if the transform is
10236
# [(1,2)]. [(1,2),(2,1)] should swap the compass values
10237
10238
parameter_mappings = {}
10239
for key in values.keys():
10240
parameter_mappings[key] = key
10241
for (old_compass_num, new_compass_num) in transforms:
10242
old_key_compass_bit = str(old_compass_num)
10243
if old_key_compass_bit == "1":
10244
old_key_compass_bit = ""
10245
new_key_compass_bit = str(new_compass_num)
10246
if new_key_compass_bit == "1":
10247
new_key_compass_bit = ""
10248
# vectors first:
10249
for key_vector_bit in ["OFS", "DIA", "ODI", "MOT"]:
10250
for axis in "X", "Y", "Z":
10251
old_key = "COMPASS_%s%s_%s" % (key_vector_bit,
10252
old_key_compass_bit,
10253
axis)
10254
new_key = "COMPASS_%s%s_%s" % (key_vector_bit,
10255
new_key_compass_bit,
10256
axis)
10257
parameter_mappings[old_key] = new_key
10258
# then non-vectorey bits:
10259
for key_bit in "SCALE", "ORIENT":
10260
old_key = "COMPASS_%s%s" % (key_bit, old_key_compass_bit)
10261
new_key = "COMPASS_%s%s" % (key_bit, new_key_compass_bit)
10262
parameter_mappings[old_key] = new_key
10263
# then a sore thumb:
10264
if old_key_compass_bit == "":
10265
old_key = "COMPASS_EXTERNAL"
10266
else:
10267
old_key = "COMPASS_EXTERN%s" % old_key_compass_bit
10268
if new_key_compass_bit == "":
10269
new_key = "COMPASS_EXTERNAL"
10270
else:
10271
new_key = "COMPASS_EXTERN%s" % new_key_compass_bit
10272
parameter_mappings[old_key] = new_key
10273
10274
for key in values.keys():
10275
newkey = parameter_mappings[key]
10276
current_value = self.get_parameter(newkey)
10277
expected_value = values[key]
10278
if abs(current_value - expected_value) > 0.001:
10279
raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" %
10280
(newkey, expected_value, current_value, str(transforms), key))
10281
10282
def CompassReordering(self):
10283
'''Test Compass reordering when priorities are changed'''
10284
originals = {
10285
"COMPASS_OFS_X": 1.1,
10286
"COMPASS_OFS_Y": 1.2,
10287
"COMPASS_OFS_Z": 1.3,
10288
"COMPASS_DIA_X": 1.4,
10289
"COMPASS_DIA_Y": 1.5,
10290
"COMPASS_DIA_Z": 1.6,
10291
"COMPASS_ODI_X": 1.7,
10292
"COMPASS_ODI_Y": 1.8,
10293
"COMPASS_ODI_Z": 1.9,
10294
"COMPASS_MOT_X": 1.91,
10295
"COMPASS_MOT_Y": 1.92,
10296
"COMPASS_MOT_Z": 1.93,
10297
"COMPASS_SCALE": 1.94,
10298
"COMPASS_ORIENT": 1,
10299
"COMPASS_EXTERNAL": 2,
10300
10301
"COMPASS_OFS2_X": 2.1,
10302
"COMPASS_OFS2_Y": 2.2,
10303
"COMPASS_OFS2_Z": 2.3,
10304
"COMPASS_DIA2_X": 2.4,
10305
"COMPASS_DIA2_Y": 2.5,
10306
"COMPASS_DIA2_Z": 2.6,
10307
"COMPASS_ODI2_X": 2.7,
10308
"COMPASS_ODI2_Y": 2.8,
10309
"COMPASS_ODI2_Z": 2.9,
10310
"COMPASS_MOT2_X": 2.91,
10311
"COMPASS_MOT2_Y": 2.92,
10312
"COMPASS_MOT2_Z": 2.93,
10313
"COMPASS_SCALE2": 2.94,
10314
"COMPASS_ORIENT2": 3,
10315
"COMPASS_EXTERN2": 4,
10316
10317
"COMPASS_OFS3_X": 3.1,
10318
"COMPASS_OFS3_Y": 3.2,
10319
"COMPASS_OFS3_Z": 3.3,
10320
"COMPASS_DIA3_X": 3.4,
10321
"COMPASS_DIA3_Y": 3.5,
10322
"COMPASS_DIA3_Z": 3.6,
10323
"COMPASS_ODI3_X": 3.7,
10324
"COMPASS_ODI3_Y": 3.8,
10325
"COMPASS_ODI3_Z": 3.9,
10326
"COMPASS_MOT3_X": 3.91,
10327
"COMPASS_MOT3_Y": 3.92,
10328
"COMPASS_MOT3_Z": 3.93,
10329
"COMPASS_SCALE3": 3.94,
10330
"COMPASS_ORIENT3": 5,
10331
"COMPASS_EXTERN3": 6,
10332
}
10333
10334
# quick sanity check to ensure all values are unique:
10335
if len(originals.values()) != len(set(originals.values())):
10336
raise NotAchievedException("Values are not all unique!")
10337
10338
self.progress("Setting parameters")
10339
self.set_parameters(originals)
10340
10341
self.reboot_sitl()
10342
10343
# no transforms means our originals should be our finals:
10344
self.test_mag_reordering_assert_mag_transform(originals, [])
10345
10346
self.start_subtest("Pushing 1st mag to 3rd")
10347
self.context_push()
10348
# now try reprioritising compass 1 to be higher than compass 0:
10349
prio1_id = self.get_parameter("COMPASS_PRIO1_ID")
10350
prio2_id = self.get_parameter("COMPASS_PRIO2_ID")
10351
prio3_id = self.get_parameter("COMPASS_PRIO3_ID")
10352
self.set_parameters({
10353
"COMPASS_PRIO1_ID": prio2_id,
10354
"COMPASS_PRIO2_ID": prio3_id,
10355
"COMPASS_PRIO3_ID": prio1_id,
10356
})
10357
10358
self.reboot_sitl()
10359
10360
self.test_mag_reordering_assert_mag_transform(originals, [
10361
(2, 1),
10362
(3, 2),
10363
(1, 3),
10364
])
10365
10366
self.progress("Setting priorities back to original order")
10367
self.set_parameters({
10368
"COMPASS_PRIO1_ID": prio1_id,
10369
"COMPASS_PRIO2_ID": prio2_id,
10370
"COMPASS_PRIO3_ID": prio3_id,
10371
})
10372
10373
self.reboot_sitl()
10374
10375
self.test_mag_reordering_assert_mag_transform(originals, [
10376
(1, 1),
10377
(2, 2),
10378
(3, 3),
10379
])
10380
10381
self.progress("And reverse ordering")
10382
self.set_parameters({
10383
"COMPASS_PRIO1_ID": prio3_id,
10384
"COMPASS_PRIO2_ID": prio2_id,
10385
"COMPASS_PRIO3_ID": prio1_id,
10386
})
10387
10388
self.reboot_sitl()
10389
10390
self.test_mag_reordering_assert_mag_transform(originals, [
10391
(1, 3),
10392
(2, 2),
10393
(3, 1),
10394
])
10395
10396
self.context_pop()
10397
10398
def SixCompassCalibrationAndReordering(self):
10399
'''Test reordering of 6 simulated compasses by changing priority and appearance order'''
10400
self.context_push()
10401
10402
total_compasses = 6
10403
10404
self.progress("Setting up 6 simulated I2C compasses with calibration")
10405
10406
# Fetch existing SIM_MAGx_DEVID values
10407
device_ids = self.get_sim_mag_devids(total_compasses)
10408
10409
# disable force saving dev_ids for subsequent boots
10410
self.set_parameter("SIM_MAG_SAVE_IDS", 0)
10411
10412
self.reboot_sitl()
10413
self.wait_ready_to_arm()
10414
10415
# Verify all 6 compasses are detected (stored in DEV_ID parameters)
10416
self.progress("Verifying 6 compasses detected in DEV_ID slots")
10417
self.check_mag_devids_detected(total_compasses)
10418
10419
# Reboot to apply changes
10420
self.progress("Rebooting to apply reordering")
10421
self.reboot_sitl()
10422
10423
def wait_correct_compass_prearm_message():
10424
# Check for correct compass prearm messages
10425
# We expect "PreArm: Compass not calibrated" but NOT
10426
# "PreArm: Compass x not found" or any other compass prearm message
10427
self.progress("Waiting for compass prearm message")
10428
self.context_collect("STATUSTEXT")
10429
msg = self.wait_statustext("PreArm: Compass", timeout=60, check_context=True)
10430
10431
# Check if we got the expected message or an unexpected one
10432
if "not found" in msg.text.lower():
10433
self.context_clear_collection("STATUSTEXT")
10434
raise NotAchievedException(f"Unexpected compass not found: {msg.text}")
10435
elif "not calibrated" in msg.text.lower():
10436
self.progress(f"Got expected prearm failure: {msg.text}")
10437
else:
10438
self.context_clear_collection("STATUSTEXT")
10439
raise NotAchievedException(f"Unexpected compass prearm message: {msg.text}")
10440
10441
self.context_clear_collection("STATUSTEXT")
10442
10443
# Change appearance order: swap positions 2 and 4
10444
# Reorder: [dev1, dev4, dev3, dev2, dev5, dev6]
10445
reordered = [device_ids[0], device_ids[3], device_ids[2],
10446
device_ids[1], device_ids[4], device_ids[5]]
10447
self.reorder_compass_appearance(reordered)
10448
10449
# Set priority for compass 4
10450
self.set_parameter("COMPASS_PRIO3_ID", device_ids[3])
10451
10452
self.reboot_sitl()
10453
wait_correct_compass_prearm_message()
10454
10455
# Verify all 6 compasses are still present (in any DEV_ID slot)
10456
self.progress("Verifying all 6 compasses still present after reordering")
10457
self.check_mag_devids_detected(total_compasses)
10458
10459
self.reorder_compass_appearance(reordered)
10460
self.progress("Setting priorities to use last three compasses")
10461
self.set_parameters({
10462
"COMPASS_PRIO1_ID": device_ids[3],
10463
"COMPASS_PRIO2_ID": device_ids[4],
10464
"COMPASS_PRIO3_ID": device_ids[5],
10465
})
10466
self.reboot_sitl()
10467
wait_correct_compass_prearm_message()
10468
self.check_mag_devids_detected(total_compasses)
10469
10470
# revert to original
10471
self.progress("Reverting to original compass priorities")
10472
self.reorder_compass_appearance(device_ids)
10473
self.set_parameters({
10474
"COMPASS_PRIO1_ID": device_ids[0],
10475
"COMPASS_PRIO2_ID": device_ids[1],
10476
"COMPASS_PRIO3_ID": device_ids[2],
10477
})
10478
self.reboot_sitl()
10479
self.wait_ready_to_arm()
10480
10481
self.progress("SixCompassCalibrationAndReordering completed successfully")
10482
self.context_pop()
10483
10484
# something about SITLCompassCalibration appears to fail
10485
# this one, so we put it first:
10486
def FixedYawCalibration(self):
10487
'''Test Fixed Yaw Calibration'''
10488
self.context_push()
10489
ex = None
10490
try:
10491
MAG_OFS_X = 100
10492
MAG_OFS_Y = 200
10493
MAG_OFS_Z = 300
10494
wanted = {
10495
"COMPASS_OFS_X": (MAG_OFS_X, 3.0),
10496
"COMPASS_OFS_Y": (MAG_OFS_Y, 3.0),
10497
"COMPASS_OFS_Z": (MAG_OFS_Z, 3.0),
10498
"COMPASS_DIA_X": 1,
10499
"COMPASS_DIA_Y": 1,
10500
"COMPASS_DIA_Z": 1,
10501
"COMPASS_ODI_X": 0,
10502
"COMPASS_ODI_Y": 0,
10503
"COMPASS_ODI_Z": 0,
10504
10505
"COMPASS_OFS2_X": (MAG_OFS_X, 3.0),
10506
"COMPASS_OFS2_Y": (MAG_OFS_Y, 3.0),
10507
"COMPASS_OFS2_Z": (MAG_OFS_Z, 3.0),
10508
"COMPASS_DIA2_X": 1,
10509
"COMPASS_DIA2_Y": 1,
10510
"COMPASS_DIA2_Z": 1,
10511
"COMPASS_ODI2_X": 0,
10512
"COMPASS_ODI2_Y": 0,
10513
"COMPASS_ODI2_Z": 0,
10514
10515
"COMPASS_OFS3_X": (MAG_OFS_X, 3.0),
10516
"COMPASS_OFS3_Y": (MAG_OFS_Y, 3.0),
10517
"COMPASS_OFS3_Z": (MAG_OFS_Z, 3.0),
10518
"COMPASS_DIA3_X": 1,
10519
"COMPASS_DIA3_Y": 1,
10520
"COMPASS_DIA3_Z": 1,
10521
"COMPASS_ODI3_X": 0,
10522
"COMPASS_ODI3_Y": 0,
10523
"COMPASS_ODI3_Z": 0,
10524
}
10525
self.set_parameters({
10526
"SIM_MAG1_OFS_X": MAG_OFS_X,
10527
"SIM_MAG1_OFS_Y": MAG_OFS_Y,
10528
"SIM_MAG1_OFS_Z": MAG_OFS_Z,
10529
10530
"SIM_MAG2_OFS_X": MAG_OFS_X,
10531
"SIM_MAG2_OFS_Y": MAG_OFS_Y,
10532
"SIM_MAG2_OFS_Z": MAG_OFS_Z,
10533
10534
"SIM_MAG3_OFS_X": MAG_OFS_X,
10535
"SIM_MAG3_OFS_Y": MAG_OFS_Y,
10536
"SIM_MAG3_OFS_Z": MAG_OFS_Z,
10537
})
10538
10539
# set to some sensible-ish initial values. If your initial
10540
# offsets are way, way off you can get some very odd effects.
10541
for param in wanted:
10542
value = 0.0
10543
if "DIA" in param:
10544
value = 1.001
10545
elif "ODI" in param:
10546
value = 0.001
10547
self.set_parameter(param, value)
10548
10549
self.zero_mag_offset_parameters()
10550
10551
# wait until we definitely know where we are:
10552
self.poll_home_position(timeout=120)
10553
10554
ss = self.assert_receive_message('SIMSTATE', verbose=True)
10555
10556
self.run_cmd(
10557
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
10558
p1=math.degrees(ss.yaw),
10559
)
10560
self.verify_parameter_values(wanted)
10561
10562
# run same command but as command_int:
10563
self.zero_mag_offset_parameters()
10564
self.run_cmd_int(
10565
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
10566
p1=math.degrees(ss.yaw),
10567
)
10568
self.verify_parameter_values(wanted)
10569
10570
self.progress("Rebooting and making sure we could arm with these values")
10571
self.reboot_sitl()
10572
self.wait_ready_to_arm(timeout=60)
10573
10574
except Exception as e:
10575
ex = e
10576
10577
self.context_pop()
10578
10579
if ex is not None:
10580
raise ex
10581
10582
def DataFlashOverMAVLink(self):
10583
'''Test DataFlash over MAVLink'''
10584
self.context_push()
10585
ex = None
10586
mavproxy = self.start_mavproxy()
10587
try:
10588
self.set_parameter("LOG_BACKEND_TYPE", 2)
10589
self.reboot_sitl()
10590
self.wait_ready_to_arm(check_prearm_bit=False)
10591
mavproxy.send('arm throttle\n')
10592
mavproxy.expect('PreArm: Logging failed')
10593
self.mavproxy_load_module(mavproxy, 'dataflash_logger')
10594
mavproxy.send("dataflash_logger set verbose 1\n")
10595
mavproxy.expect('logging started')
10596
mavproxy.send("dataflash_logger set verbose 0\n")
10597
self.delay_sim_time(1)
10598
self.do_timesync_roundtrip() # drain COMMAND_ACK from that failed arm
10599
self.arm_vehicle()
10600
tstart = self.get_sim_time()
10601
last_status = 0
10602
mavproxy.send('repeat add 1 dataflash_logger status\n')
10603
while True:
10604
now = self.get_sim_time()
10605
if now - tstart > 60:
10606
break
10607
if now - last_status > 5:
10608
last_status = now
10609
# seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:0
10610
mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")
10611
rate = float(mavproxy.match.group(1))
10612
self.progress("Rate: %f" % rate)
10613
desired_rate = 50
10614
if self.valgrind or self.callgrind:
10615
desired_rate /= 10
10616
if rate < desired_rate:
10617
raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))
10618
self.disarm_vehicle()
10619
mavproxy.send('repeat remove 0\n')
10620
except Exception as e:
10621
self.print_exception_caught(e)
10622
self.disarm_vehicle()
10623
ex = e
10624
self.mavproxy_unload_module(mavproxy, 'dataflash_logger')
10625
10626
# the following things won't work - but they shouldn't die either:
10627
self.mavproxy_load_module(mavproxy, 'log')
10628
10629
self.progress("Try log list")
10630
mavproxy.send("log list\n")
10631
mavproxy.expect("No logs")
10632
10633
self.progress("Try log erase")
10634
mavproxy.send("log erase\n")
10635
# no response to this...
10636
10637
self.progress("Try log download")
10638
mavproxy.send("log download 1\n")
10639
# no response to this...
10640
10641
self.mavproxy_unload_module(mavproxy, 'log')
10642
10643
self.context_pop()
10644
10645
self.stop_mavproxy(mavproxy)
10646
self.reboot_sitl()
10647
if ex is not None:
10648
raise ex
10649
10650
def DataFlash(self):
10651
"""Test DataFlash SITL backend"""
10652
self.context_push()
10653
ex = None
10654
mavproxy = self.start_mavproxy()
10655
try:
10656
self.set_parameter("LOG_BACKEND_TYPE", 4)
10657
self.set_parameter("LOG_FILE_DSRMROT", 1)
10658
self.set_parameter("LOG_BLK_RATEMAX", 1)
10659
self.reboot_sitl()
10660
# First log created here, but we are in chip erase so ignored
10661
mavproxy.send("module load log\n")
10662
mavproxy.send("log erase\n")
10663
mavproxy.expect("Chip erase complete")
10664
10665
self.wait_ready_to_arm()
10666
if self.is_copter() or self.is_plane():
10667
self.set_autodisarm_delay(0)
10668
self.arm_vehicle()
10669
self.delay_sim_time(5)
10670
self.disarm_vehicle()
10671
# First log created here
10672
self.delay_sim_time(2)
10673
self.arm_vehicle()
10674
self.delay_sim_time(5)
10675
self.disarm_vehicle()
10676
# Second log created here
10677
self.delay_sim_time(2)
10678
mavproxy.send("log list\n")
10679
mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
10680
log_num = int(mavproxy.match.group(1))
10681
numlogs = int(mavproxy.match.group(2))
10682
lastlog = int(mavproxy.match.group(3))
10683
size = int(mavproxy.match.group(4))
10684
if numlogs != 2 or log_num != 1 or size <= 0:
10685
raise NotAchievedException("Unexpected log information %d %d %d" % (log_num, numlogs, lastlog))
10686
self.progress("Log size: %d" % size)
10687
self.reboot_sitl()
10688
# This starts a new log with a time of 0, wait for arm so that we can insert the correct time
10689
self.wait_ready_to_arm()
10690
# Third log created here
10691
mavproxy.send("log list\n")
10692
mavproxy.expect("Log 1 numLogs 3 lastLog 3 size")
10693
10694
# Download second and third logs
10695
mavproxy.send("log download 2 logs/dataflash-log-002.BIN\n")
10696
mavproxy.expect("Finished downloading", timeout=120)
10697
mavproxy.send("log download 3 logs/dataflash-log-003.BIN\n")
10698
mavproxy.expect("Finished downloading", timeout=120)
10699
10700
# Erase the logs
10701
mavproxy.send("log erase\n")
10702
mavproxy.expect("Chip erase complete")
10703
10704
except Exception as e:
10705
self.print_exception_caught(e)
10706
ex = e
10707
mavproxy.send("module unload log\n")
10708
self.stop_mavproxy(mavproxy)
10709
self.context_pop()
10710
self.reboot_sitl()
10711
if ex is not None:
10712
raise ex
10713
10714
def validate_log_file(self, logname, header_errors=0):
10715
"""Validate the contents of a log file"""
10716
# read the downloaded log - it must parse without error
10717
class Capturing(list):
10718
def __enter__(self):
10719
self._stderr = sys.stderr
10720
sys.stderr = self._stringio = io.StringIO()
10721
return self
10722
10723
def __exit__(self, *args):
10724
self.extend(self._stringio.getvalue().splitlines())
10725
del self._stringio # free up some memory
10726
sys.stderr = self._stderr
10727
10728
with Capturing() as df_output:
10729
try:
10730
mlog = mavutil.mavlink_connection(logname)
10731
while True:
10732
m = mlog.recv_match()
10733
if m is None:
10734
break
10735
except Exception as e:
10736
raise NotAchievedException("Error reading log file %s: %s" % (logname, str(e)))
10737
10738
herrors = 0
10739
10740
for msg in df_output:
10741
if msg.startswith("bad header") or msg.startswith("unknown msg type"):
10742
herrors = herrors + 1
10743
10744
if herrors > header_errors:
10745
raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors))
10746
10747
def DataFlashErase(self):
10748
"""Test that erasing the dataflash chip and creating a new log is error free"""
10749
mavproxy = self.start_mavproxy()
10750
10751
ex = None
10752
self.context_push()
10753
try:
10754
self.set_parameter("LOG_BACKEND_TYPE", 4)
10755
self.reboot_sitl()
10756
mavproxy.send("module load log\n")
10757
mavproxy.send("log erase\n")
10758
mavproxy.expect("Chip erase complete")
10759
self.set_parameter("LOG_DISARMED", 1)
10760
self.delay_sim_time(3)
10761
self.set_parameter("LOG_DISARMED", 0)
10762
mavproxy.send("log download 1 logs/dataflash-log-erase.BIN\n")
10763
mavproxy.expect("Finished downloading", timeout=120)
10764
# read the downloaded log - it must parse without error
10765
self.validate_log_file("logs/dataflash-log-erase.BIN")
10766
10767
self.start_subtest("Test file wrapping results in a valid file")
10768
# roughly 4mb
10769
self.set_parameter("LOG_FILE_DSRMROT", 1)
10770
self.set_parameter("LOG_BITMASK", 131071)
10771
self.wait_ready_to_arm()
10772
if self.is_copter() or self.is_plane():
10773
self.set_autodisarm_delay(0)
10774
self.arm_vehicle()
10775
self.delay_sim_time(30)
10776
self.disarm_vehicle()
10777
# roughly 4mb
10778
self.arm_vehicle()
10779
self.delay_sim_time(30)
10780
self.disarm_vehicle()
10781
# roughly 9mb, should wrap around
10782
self.arm_vehicle()
10783
self.delay_sim_time(50)
10784
self.disarm_vehicle()
10785
# make sure we have finished logging
10786
self.delay_sim_time(15)
10787
mavproxy.send("log list\n")
10788
try:
10789
mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
10790
except pexpect.TIMEOUT as e:
10791
if self.sitl_is_running():
10792
self.progress("SITL is running")
10793
else:
10794
self.progress("SITL is NOT running")
10795
raise NotAchievedException("Received %s" % str(e))
10796
if int(mavproxy.match.group(2)) != 3:
10797
raise NotAchievedException("Expected 3 logs got %s" % (mavproxy.match.group(2)))
10798
10799
mavproxy.send("log download 1 logs/dataflash-log-erase2.BIN\n")
10800
mavproxy.expect("Finished downloading", timeout=120)
10801
self.validate_log_file("logs/dataflash-log-erase2.BIN", 1)
10802
10803
mavproxy.send("log download latest logs/dataflash-log-erase3.BIN\n")
10804
mavproxy.expect("Finished downloading", timeout=120)
10805
self.validate_log_file("logs/dataflash-log-erase3.BIN", 1)
10806
10807
# clean up
10808
mavproxy.send("log erase\n")
10809
mavproxy.expect("Chip erase complete")
10810
10811
# clean up
10812
mavproxy.send("log erase\n")
10813
mavproxy.expect("Chip erase complete")
10814
10815
except Exception as e:
10816
self.print_exception_caught(e)
10817
ex = e
10818
10819
mavproxy.send("module unload log\n")
10820
10821
self.context_pop()
10822
self.reboot_sitl()
10823
10824
self.stop_mavproxy(mavproxy)
10825
10826
if ex is not None:
10827
raise ex
10828
10829
def ArmFeatures(self):
10830
'''Arm features'''
10831
# TEST ARMING/DISARM
10832
self.delay_sim_time(12) # wait for gyros/accels to be happy
10833
if self.get_parameter("ARMING_SKIPCHK") != 0 and not self.is_sub():
10834
raise ValueError("Arming skipped checks should be 0")
10835
if not self.is_sub() and not self.is_tracker():
10836
self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests
10837
if self.is_copter():
10838
interlock_channel = 8 # Plane got flighmode_ch on channel 8
10839
if not self.is_heli(): # heli don't need interlock option
10840
interlock_channel = 9
10841
self.set_parameter("RC%u_OPTION" % interlock_channel, 32)
10842
self.set_rc(interlock_channel, 1000)
10843
self.zero_throttle()
10844
# Disable auto disarm for next tests
10845
# Rover and Sub don't have auto disarm
10846
if self.is_copter() or self.is_plane():
10847
self.set_autodisarm_delay(0)
10848
self.start_subtest("Test normal arm and disarm features")
10849
self.wait_ready_to_arm()
10850
self.progress("default arm_vehicle() call")
10851
if not self.arm_vehicle():
10852
raise NotAchievedException("Failed to ARM")
10853
self.progress("default disarm_vehicle() call")
10854
self.disarm_vehicle()
10855
10856
self.start_subtest("Arm/disarm vehicle with COMMAND_INT")
10857
self.run_cmd_int(
10858
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10859
p1=1, # ARM
10860
)
10861
self.run_cmd_int(
10862
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10863
p1=0, # DISARM
10864
)
10865
10866
self.progress("arm with mavproxy")
10867
mavproxy = self.start_mavproxy()
10868
if not self.mavproxy_arm_vehicle(mavproxy):
10869
raise NotAchievedException("Failed to ARM")
10870
self.progress("disarm with mavproxy")
10871
self.mavproxy_disarm_vehicle(mavproxy)
10872
self.stop_mavproxy(mavproxy)
10873
10874
if not self.is_sub():
10875
self.start_subtest("Test arm with rc input")
10876
self.arm_motors_with_rc_input()
10877
self.progress("disarm with rc input")
10878
if self.is_balancebot():
10879
self.progress("balancebot can't disarm with RC input")
10880
self.disarm_vehicle()
10881
else:
10882
self.disarm_motors_with_rc_input()
10883
10884
self.start_subtest("Test arm and disarm with switch")
10885
arming_switch = 7
10886
self.set_parameter("RC%d_OPTION" % arming_switch, 153)
10887
self.set_rc(arming_switch, 1000)
10888
# delay so a transition is seen by the RC switch code:
10889
self.delay_sim_time(0.5)
10890
self.arm_motors_with_switch(arming_switch)
10891
self.disarm_motors_with_switch(arming_switch)
10892
self.set_rc(arming_switch, 1000)
10893
10894
if self.is_copter():
10895
self.start_subtest("Test arming failure with throttle too high")
10896
self.set_rc(3, 1800)
10897
try:
10898
if self.arm_vehicle():
10899
raise NotAchievedException("Armed when throttle too high")
10900
except ValueError:
10901
pass
10902
try:
10903
self.arm_motors_with_rc_input()
10904
except NotAchievedException:
10905
pass
10906
if self.armed():
10907
raise NotAchievedException(
10908
"Armed via RC when throttle too high")
10909
try:
10910
self.arm_motors_with_switch(arming_switch)
10911
except NotAchievedException:
10912
pass
10913
if self.armed():
10914
raise NotAchievedException("Armed via RC when switch too high")
10915
self.zero_throttle()
10916
self.set_rc(arming_switch, 1000)
10917
10918
# Sub doesn't have 'stick commands'
10919
self.start_subtest("Test arming failure with ARMING_RUDDER=0")
10920
self.set_parameter("ARMING_RUDDER", 0)
10921
try:
10922
self.arm_motors_with_rc_input()
10923
except NotAchievedException:
10924
pass
10925
if self.armed():
10926
raise NotAchievedException(
10927
"Armed with rudder when ARMING_RUDDER=0")
10928
self.start_subtest("Test disarming failure with ARMING_RUDDER=0")
10929
self.arm_vehicle()
10930
try:
10931
self.disarm_motors_with_rc_input(watch_for_disabled=True)
10932
except NotAchievedException:
10933
pass
10934
if not self.armed():
10935
raise NotAchievedException(
10936
"Disarmed with rudder when ARMING_RUDDER=0")
10937
self.disarm_vehicle()
10938
self.wait_heartbeat()
10939
self.start_subtest("Test disarming failure with ARMING_RUDDER=1")
10940
self.set_parameter("ARMING_RUDDER", 1)
10941
self.arm_vehicle()
10942
try:
10943
self.disarm_motors_with_rc_input()
10944
except NotAchievedException:
10945
pass
10946
if not self.armed():
10947
raise NotAchievedException(
10948
"Disarmed with rudder with ARMING_RUDDER=1")
10949
self.disarm_vehicle()
10950
self.wait_heartbeat()
10951
self.set_parameter("ARMING_RUDDER", 2)
10952
10953
if self.is_copter():
10954
self.start_subtest("Test arming failure with interlock enabled")
10955
self.set_rc(interlock_channel, 2000)
10956
try:
10957
self.arm_motors_with_rc_input()
10958
except NotAchievedException:
10959
pass
10960
if self.armed():
10961
raise NotAchievedException(
10962
"Armed with RC input when interlock enabled")
10963
try:
10964
self.arm_motors_with_switch(arming_switch)
10965
except NotAchievedException:
10966
pass
10967
if self.armed():
10968
raise NotAchievedException("Armed with switch when interlock enabled")
10969
self.disarm_vehicle()
10970
self.wait_heartbeat()
10971
self.set_rc(arming_switch, 1000)
10972
self.set_rc(interlock_channel, 1000)
10973
if self.is_heli():
10974
self.start_subtest("Test motor interlock enable can't be set while disarmed")
10975
self.set_rc(interlock_channel, 2000)
10976
channel_field = "servo%u_raw" % interlock_channel
10977
interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel)
10978
tstart = self.get_sim_time()
10979
while True:
10980
if self.get_sim_time_cached() - tstart > 20:
10981
self.set_rc(interlock_channel, 1000)
10982
break # success!
10983
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
10984
blocking=True,
10985
timeout=2)
10986
if m is None:
10987
continue
10988
m_value = getattr(m, channel_field, None)
10989
if m_value is None:
10990
self.set_rc(interlock_channel, 1000)
10991
raise ValueError("Message has no %s field" %
10992
channel_field)
10993
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
10994
(channel_field, m_value, interlock_value))
10995
if m_value != interlock_value:
10996
self.set_rc(interlock_channel, 1000)
10997
raise NotAchievedException("Motor interlock was changed while disarmed")
10998
self.set_rc(interlock_channel, 1000)
10999
11000
self.start_subtest("Test all mode arming")
11001
self.wait_ready_to_arm()
11002
11003
if self.arming_test_mission() is not None:
11004
self.load_mission(self.arming_test_mission())
11005
11006
for mode in self.mav.mode_mapping():
11007
self.drain_mav()
11008
self.start_subtest("Mode : %s" % mode)
11009
if mode == "FOLLOW":
11010
self.set_parameter("FOLL_ENABLE", 1)
11011
if mode in self.get_normal_armable_modes_list():
11012
self.progress("Armable mode : %s" % mode)
11013
self.change_mode(mode)
11014
self.arm_vehicle()
11015
self.disarm_vehicle()
11016
self.progress("PASS arm mode : %s" % mode)
11017
if mode in self.get_not_armable_mode_list():
11018
if mode in self.get_not_disarmed_settable_modes_list():
11019
self.progress("Not settable mode : %s" % mode)
11020
try:
11021
self.change_mode(mode, timeout=15)
11022
except AutoTestTimeoutException:
11023
self.progress("PASS not able to set mode : %s disarmed" % mode)
11024
except ValueError:
11025
self.progress("PASS not able to set mode : %s disarmed" % mode)
11026
else:
11027
self.progress("Not armable mode : %s" % mode)
11028
self.change_mode(mode)
11029
self.run_cmd(
11030
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
11031
p1=1, # ARM
11032
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
11033
)
11034
self.progress("PASS not able to arm in mode : %s" % mode)
11035
if mode in self.get_position_armable_modes_list():
11036
self.progress("Armable mode needing Position : %s" % mode)
11037
self.wait_ekf_happy()
11038
self.change_mode(mode)
11039
self.arm_vehicle()
11040
self.wait_heartbeat()
11041
self.disarm_vehicle()
11042
self.progress("PASS arm mode : %s" % mode)
11043
self.progress("Not armable mode without Position : %s" % mode)
11044
self.wait_gps_disable()
11045
self.change_mode(mode)
11046
self.run_cmd(
11047
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
11048
p1=1, # ARM
11049
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
11050
)
11051
self.set_parameter("SIM_GPS1_ENABLE", 1)
11052
self.wait_ekf_happy() # EKF may stay unhappy for a while
11053
self.progress("PASS not able to arm without Position in mode : %s" % mode)
11054
if mode in self.get_no_position_not_settable_modes_list():
11055
self.progress("Setting mode need Position : %s" % mode)
11056
self.wait_ekf_happy()
11057
self.wait_gps_disable()
11058
try:
11059
self.change_mode(mode, timeout=15)
11060
except AutoTestTimeoutException:
11061
self.set_parameter("SIM_GPS1_ENABLE", 1)
11062
self.progress("PASS not able to set mode without Position : %s" % mode)
11063
except ValueError:
11064
self.set_parameter("SIM_GPS1_ENABLE", 1)
11065
self.progress("PASS not able to set mode without Position : %s" % mode)
11066
if mode == "FOLLOW":
11067
self.set_parameter("FOLL_ENABLE", 0)
11068
self.change_mode(self.default_mode())
11069
if self.armed():
11070
self.disarm_vehicle()
11071
11072
# we should find at least one Armed event and one disarmed
11073
# event, and at least one ARM message for arm and disarm
11074
wants = set([
11075
("Armed EV message", "EV", lambda e : e.Id == 10),
11076
("Disarmed EV message", "EV", lambda e : e.Id == 11),
11077
("Armed ARM message", "ARM", lambda a : a.ArmState == 1),
11078
("Disarmed ARM message", "ARM", lambda a : a.ArmState == 0),
11079
])
11080
11081
dfreader = self.dfreader_for_current_onboard_log()
11082
types = set()
11083
for (name, msgtype, l) in wants:
11084
types.add(msgtype)
11085
11086
while True:
11087
m = dfreader.recv_match(type=types)
11088
if m is None:
11089
break
11090
wantscopy = copy.copy(wants)
11091
for want in wantscopy:
11092
(name, msgtype, l) = want
11093
if m.get_type() != msgtype:
11094
continue
11095
if l(m):
11096
self.progress("Found %s" % name)
11097
wants.discard(want)
11098
if len(wants) == 0:
11099
break
11100
11101
if len(wants):
11102
msg = ", ".join([x[0] for x in wants])
11103
raise NotAchievedException("Did not find (%s)" % msg)
11104
11105
self.progress("ALL PASS")
11106
# TODO : Test arming magic;
11107
11108
def measure_message_rate(self, victim_message, timeout=10, mav=None):
11109
if mav is None:
11110
mav = self.mav
11111
tstart = self.get_sim_time()
11112
count = 0
11113
while self.get_sim_time_cached() < tstart + timeout:
11114
m = mav.recv_match(
11115
type=victim_message,
11116
blocking=True,
11117
timeout=0.1
11118
)
11119
if m is not None:
11120
count += 1
11121
if mav != self.mav:
11122
self.drain_mav(self.mav)
11123
11124
time_delta = self.get_sim_time_cached() - tstart
11125
self.progress("%s count after %f seconds: %u" %
11126
(victim_message, time_delta, count))
11127
return count/time_delta
11128
11129
def rate_to_interval_us(self, rate):
11130
return 1/float(rate)*1000000.0
11131
11132
def interval_us_to_rate(self, interval):
11133
if interval == 0:
11134
raise ValueError("Zero interval is infinite rate")
11135
return 1000000.0/float(interval)
11136
11137
def set_message_rate_hz(self, id, rate_hz, mav=None, run_cmd=None):
11138
'''set a message rate in Hz; 0 for original, -1 to disable'''
11139
if run_cmd is None:
11140
run_cmd = self.run_cmd
11141
if isinstance(id, str):
11142
id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id)
11143
if rate_hz == 0 or rate_hz == -1:
11144
set_interval = rate_hz
11145
else:
11146
set_interval = self.rate_to_interval_us(rate_hz)
11147
run_cmd(
11148
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
11149
p1=id,
11150
p2=set_interval,
11151
mav=mav,
11152
)
11153
11154
def get_message_rate_hz(self, id, mav=None, run_cmd=None):
11155
'''return rate message is being sent, in Hz'''
11156
if run_cmd is None:
11157
run_cmd = self.run_cmd
11158
11159
interval = self.get_message_interval(id, mav=mav, run_cmd=run_cmd)
11160
return self.interval_us_to_rate(interval)
11161
11162
def send_get_message_interval(self, victim_message, mav=None):
11163
if mav is None:
11164
mav = self.mav
11165
if isinstance(victim_message, str):
11166
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
11167
mav.mav.command_long_send(
11168
1,
11169
1,
11170
mavutil.mavlink.MAV_CMD_GET_MESSAGE_INTERVAL,
11171
1, # confirmation
11172
float(victim_message),
11173
0,
11174
0,
11175
0,
11176
0,
11177
0,
11178
0)
11179
11180
def get_message_interval(self, victim_message, mav=None, run_cmd=None):
11181
'''returns message interval in microseconds'''
11182
if run_cmd is None:
11183
run_cmd = self.run_cmd
11184
11185
self.send_get_message_interval(victim_message, mav=mav)
11186
m = self.assert_receive_message('MESSAGE_INTERVAL', mav=mav)
11187
11188
if isinstance(victim_message, str):
11189
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
11190
if m.message_id != victim_message:
11191
raise NotAchievedException(f"Unexpected ID in MESSAGE_INTERVAL (want={victim_message}, got={m.message_id}")
11192
11193
return m.interval_us
11194
11195
def set_message_interval(self, victim_message, interval_us, mav=None):
11196
'''sets message interval in microseconds'''
11197
if isinstance(victim_message, str):
11198
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
11199
self.run_cmd(
11200
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
11201
p1=victim_message,
11202
p2=interval_us,
11203
mav=mav,
11204
)
11205
11206
def test_rate(self,
11207
desc,
11208
in_rate,
11209
expected_rate
11210
, mav=None,
11211
victim_message="VFR_HUD",
11212
ndigits=0,
11213
message_rate_sample_period=10):
11214
if mav is None:
11215
mav = self.mav
11216
11217
self.progress("###### %s" % desc)
11218
self.progress("Setting rate to %f" % round(in_rate, ndigits=ndigits))
11219
11220
self.set_message_rate_hz(victim_message, in_rate, mav=mav)
11221
11222
new_measured_rate = self.measure_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav)
11223
self.progress(
11224
"Measured rate: %f (want %f)" %
11225
(round(new_measured_rate, ndigits=ndigits),
11226
round(expected_rate, ndigits=ndigits))
11227
)
11228
notachieved_ex = None
11229
if round(new_measured_rate, ndigits=ndigits) != round(expected_rate, ndigits=ndigits):
11230
notachieved_ex = NotAchievedException(
11231
"Rate not achieved (got %f want %f)" %
11232
(round(new_measured_rate, ndigits),
11233
round(expected_rate, ndigits)))
11234
11235
# make sure get_message_interval works:
11236
self.send_get_message_interval(victim_message, mav=mav)
11237
11238
m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=30, mav=mav)
11239
11240
if in_rate == 0:
11241
want = self.rate_to_interval_us(expected_rate)
11242
elif in_rate == -1:
11243
want = in_rate
11244
else:
11245
want = self.rate_to_interval_us(in_rate)
11246
11247
if m.interval_us != want:
11248
raise NotAchievedException("Did not read same interval back from autopilot: want=%d got=%d)" %
11249
(want, m.interval_us))
11250
m = self.assert_receive_message('COMMAND_ACK', mav=mav)
11251
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
11252
raise NotAchievedException("Expected ACCEPTED for reading message interval")
11253
11254
if notachieved_ex is not None:
11255
raise notachieved_ex
11256
11257
def SET_MESSAGE_INTERVAL(self):
11258
'''Test MAV_CMD_SET_MESSAGE_INTERVAL'''
11259
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
11260
self.reboot_sitl() # needed for CAM1_TYPE to take effect
11261
self.start_subtest('Basic tests')
11262
self.test_set_message_interval_basic()
11263
self.start_subtest('Many-message tests')
11264
self.test_set_message_interval_many()
11265
11266
def MESSAGE_INTERVAL_COMMAND_INT(self):
11267
'''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT'''
11268
original_rate = round(self.measure_message_rate("VFR_HUD", 20))
11269
self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)
11270
if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1:
11271
raise NotAchievedException("Did not set rate")
11272
11273
# Try setting a rate well beyond SCHED_LOOP_RATE
11274
self.run_cmd(
11275
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
11276
p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD,
11277
p2=self.rate_to_interval_us(800),
11278
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
11279
)
11280
11281
self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT")
11282
# 148 is AUTOPILOT_VERSION:
11283
self.context_collect('AUTOPILOT_VERSION')
11284
self.run_cmd_int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, 148)
11285
self.delay_sim_time(2)
11286
count = len(self.context_collection('AUTOPILOT_VERSION'))
11287
if count != 1:
11288
raise NotAchievedException(f"Did not get single AUTOPILOT_VERSION message (count={count}")
11289
11290
def test_set_message_interval_many(self):
11291
messages = [
11292
'CAMERA_FEEDBACK',
11293
'RAW_IMU',
11294
'ATTITUDE',
11295
]
11296
ex = None
11297
try:
11298
rate = 5
11299
for message in messages:
11300
self.set_message_rate_hz(message, rate)
11301
for message in messages:
11302
self.assert_message_rate_hz(message, rate)
11303
except Exception as e:
11304
self.print_exception_caught(e)
11305
ex = e
11306
11307
# reset message rates to default:
11308
for message in messages:
11309
self.set_message_rate_hz(message, -1)
11310
11311
if ex is not None:
11312
raise ex
11313
11314
def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0, mav=None):
11315
if mav is None:
11316
mav = self.mav
11317
self.drain_mav(mav)
11318
rate = round(self.measure_message_rate(message, sample_period, mav=mav), ndigits=ndigits)
11319
self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits)))
11320
if rate != want_rate:
11321
raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate))
11322
11323
def test_set_message_interval_basic(self):
11324
ex = None
11325
try:
11326
rate = round(self.measure_message_rate("VFR_HUD", 20))
11327
self.progress("Initial rate: %u" % rate)
11328
11329
self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD")
11330
# this assumes the streamrates have not been played with:
11331
self.test_rate("Resetting original rate using 0-value", 0, rate)
11332
self.test_rate("Disabling using -1-value", -1, 0)
11333
self.test_rate("Resetting original rate", 0, rate)
11334
11335
self.progress("try getting a message which is not ordinarily streamed out")
11336
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))
11337
if rate != 0:
11338
raise PreconditionFailedException("Already getting CAMERA_FEEDBACK")
11339
self.progress("try various message rates")
11340
for want_rate in range(5, 14):
11341
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,
11342
want_rate)
11343
self.assert_message_rate_hz('CAMERA_FEEDBACK', want_rate)
11344
11345
self.progress("try at the main loop rate")
11346
# have to reset the speedup as MAVProxy can't keep up otherwise
11347
old_speedup = self.get_parameter("SIM_SPEEDUP")
11348
self.set_parameter("SIM_SPEEDUP", 1.0)
11349
# ArduPilot currently limits message rate to 80% of main loop rate:
11350
want_rate = self.get_parameter("SCHED_LOOP_RATE") * 0.8
11351
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,
11352
want_rate)
11353
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))
11354
self.set_parameter("SIM_SPEEDUP", old_speedup)
11355
self.progress("Want=%f got=%f" % (want_rate, rate))
11356
if abs(rate - want_rate) > 2:
11357
raise NotAchievedException("Did not get expected rate")
11358
11359
self.drain_mav()
11360
11361
non_existant_id = 145
11362
self.send_get_message_interval(non_existant_id)
11363
m = self.assert_receive_message('MESSAGE_INTERVAL')
11364
if m.interval_us != 0:
11365
raise NotAchievedException("Supposed to get 0 back for unsupported stream")
11366
m = self.assert_receive_message('COMMAND_ACK')
11367
if m.result != mavutil.mavlink.MAV_RESULT_FAILED:
11368
raise NotAchievedException("Getting rate of unsupported message is a failure")
11369
11370
except Exception as e:
11371
self.print_exception_caught(e)
11372
ex = e
11373
11374
self.progress("Resetting CAMERA_FEEDBACK rate to default rate")
11375
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, 0)
11376
self.assert_message_rate_hz('CAMERA_FEEDBACK', 0)
11377
11378
if ex is not None:
11379
raise ex
11380
11381
def send_poll_message(self, message_id, target_sysid=None, target_compid=None, quiet=False, mav=None):
11382
if mav is None:
11383
mav = self.mav
11384
if isinstance(message_id, str):
11385
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
11386
self.send_cmd(
11387
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
11388
p1=message_id,
11389
target_sysid=target_sysid,
11390
target_compid=target_compid,
11391
quiet=quiet,
11392
mav=mav,
11393
)
11394
11395
def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None):
11396
if mav is None:
11397
mav = self.mav
11398
if target_sysid is None:
11399
target_sysid = self.sysid_thismav()
11400
if target_compid is None:
11401
target_compid = 1
11402
if isinstance(message_id, str):
11403
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
11404
tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work
11405
self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid)
11406
self.run_cmd_get_ack(
11407
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
11408
mavutil.mavlink.MAV_RESULT_ACCEPTED,
11409
timeout,
11410
quiet=quiet,
11411
mav=mav,
11412
)
11413
while True:
11414
if self.get_sim_time_cached() - tstart > timeout:
11415
raise NotAchievedException("Did not receive polled message")
11416
m = mav.recv_match(blocking=True,
11417
timeout=0.1)
11418
if self.mav != mav:
11419
self.drain_mav()
11420
if m is None:
11421
continue
11422
if m.id != message_id:
11423
continue
11424
if (m.get_srcSystem() != target_sysid or
11425
m.get_srcComponent() != target_compid):
11426
continue
11427
return m
11428
11429
def get_messages_frame(self, msg_names):
11430
'''try to get a "frame" of named messages - a set of messages as close
11431
in time as possible'''
11432
msgs = {}
11433
11434
def get_msgs(mav, m):
11435
t = m.get_type()
11436
if t in msg_names:
11437
msgs[t] = m
11438
self.do_timesync_roundtrip()
11439
self.install_message_hook(get_msgs)
11440
for msg_name in msg_names:
11441
self.send_poll_message(msg_name)
11442
while True:
11443
self.mav.recv_match(blocking=True)
11444
if len(msgs.keys()) == len(msg_names):
11445
break
11446
11447
self.remove_message_hook(get_msgs)
11448
11449
return msgs
11450
11451
def REQUEST_MESSAGE(self, timeout=60):
11452
'''Test MAV_CMD_REQUEST_MESSAGE'''
11453
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
11454
self.reboot_sitl() # needed for CAM1_TYPE to take effect
11455
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 10))
11456
if rate != 0:
11457
raise PreconditionFailedException("Receiving camera feedback")
11458
self.poll_message("CAMERA_FEEDBACK")
11459
11460
def clear_mission(self, mission_type, target_system=1, target_component=1):
11461
'''clear mision_type from autopilot. Note that this does NOT actually
11462
send a MISSION_CLEAR_ALL message
11463
'''
11464
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_ALL:
11465
# recurse
11466
if not self.is_tracker() and not self.is_blimp():
11467
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
11468
if not self.is_blimp():
11469
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
11470
if not self.is_sub() and not self.is_tracker() and not self.is_blimp():
11471
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
11472
self.last_wp_load = time.time()
11473
return
11474
11475
self.mav.mav.mission_count_send(target_system,
11476
target_component,
11477
0,
11478
mission_type)
11479
self.assert_received_message_field_values('MISSION_ACK', {
11480
"target_system": self.mav.mav.srcSystem,
11481
"target_component": self.mav.mav.srcComponent,
11482
"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,
11483
})
11484
11485
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
11486
self.last_wp_load = time.time()
11487
11488
def clear_fence_using_mavproxy(self, mavproxy, timeout=10):
11489
mavproxy.send("fence clear\n")
11490
tstart = self.get_sim_time_cached()
11491
while True:
11492
now = self.get_sim_time_cached()
11493
if now - tstart > timeout:
11494
raise AutoTestTimeoutException("FENCE_TOTAL did not go to zero")
11495
if self.get_parameter("FENCE_TOTAL") == 0:
11496
break
11497
11498
def clear_fence(self):
11499
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
11500
11501
# Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa
11502
def ConfigErrorLoop(self):
11503
'''test the sensor config error loop works and that parameter sets are persistent'''
11504
parameter_name = "SERVO8_MIN"
11505
old_parameter_value = self.get_parameter(parameter_name)
11506
old_sim_baro_count = self.get_parameter("SIM_BARO_COUNT")
11507
new_parameter_value = old_parameter_value + 5
11508
ex = None
11509
try:
11510
self.set_parameter("STAT_BOOTCNT", 0)
11511
self.set_parameter("SIM_BARO_COUNT", -1)
11512
11513
if self.is_tracker():
11514
# starts armed...
11515
self.progress("Disarming tracker")
11516
self.disarm_vehicle(force=True)
11517
11518
self.reboot_sitl(required_bootcount=1)
11519
self.progress("Waiting for 'Config error'")
11520
# SYSTEM_TIME not sent in config error loop:
11521
self.wait_statustext("Config error", wallclock_timeout=True)
11522
self.progress("Setting %s to %f" % (parameter_name, new_parameter_value))
11523
self.set_parameter(parameter_name, new_parameter_value)
11524
except Exception as e:
11525
ex = e
11526
11527
self.progress("Resetting SIM_BARO_COUNT")
11528
self.set_parameter("SIM_BARO_COUNT", old_sim_baro_count)
11529
11530
if self.is_tracker():
11531
# starts armed...
11532
self.progress("Disarming tracker")
11533
self.disarm_vehicle(force=True)
11534
11535
self.progress("Calling reboot-sitl ")
11536
self.reboot_sitl(required_bootcount=2)
11537
11538
if ex is not None:
11539
raise ex
11540
11541
if self.get_parameter(parameter_name) != new_parameter_value:
11542
raise NotAchievedException("Parameter value did not stick")
11543
11544
def InitialMode(self):
11545
'''Test initial mode switching'''
11546
if self.is_copter():
11547
init_mode = (9, "LAND")
11548
if self.is_rover():
11549
init_mode = (4, "HOLD")
11550
if self.is_plane():
11551
init_mode = (13, "TAKEOFF")
11552
if self.is_tracker():
11553
init_mode = (1, "STOP")
11554
if self.is_sub():
11555
return # NOT Supported yet
11556
self.context_push()
11557
self.set_parameter("SIM_RC_FAIL", 1)
11558
self.progress("Setting INITIAL_MODE to %s" % init_mode[1])
11559
self.set_parameter("INITIAL_MODE", init_mode[0])
11560
self.reboot_sitl()
11561
self.wait_mode(init_mode[1])
11562
self.progress("Testing back mode switch")
11563
self.set_parameter("SIM_RC_FAIL", 0)
11564
self.wait_for_mode_switch_poll()
11565
self.context_pop()
11566
self.reboot_sitl()
11567
11568
def Gripper(self):
11569
'''Test gripper'''
11570
self.GripperType(1) # servo
11571
self.GripperType(2) # EPM
11572
11573
def GripperType(self, gripper_type):
11574
'''test specific gripper type'''
11575
self.context_push()
11576
self.set_parameters({
11577
"GRIP_ENABLE": 1,
11578
"GRIP_GRAB": 2000,
11579
"GRIP_RELEASE": 1000,
11580
"GRIP_TYPE": gripper_type,
11581
"SIM_GRPS_ENABLE": 1,
11582
"SIM_GRPS_PIN": 8,
11583
"SERVO8_FUNCTION": 28,
11584
"SERVO8_MIN": 1000,
11585
"SERVO8_MAX": 2000,
11586
"SERVO9_MIN": 1000,
11587
"SERVO9_MAX": 2000,
11588
"RC9_OPTION": 19,
11589
})
11590
self.set_rc(9, 1500)
11591
self.reboot_sitl()
11592
self.progress("Waiting for ready to arm")
11593
self.wait_ready_to_arm()
11594
self.progress("Test gripper with RC9_OPTION")
11595
self.progress("Releasing load")
11596
# non strict string matching because of catching text issue....
11597
self.context_collect('STATUSTEXT')
11598
self.set_rc(9, 1000)
11599
self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)
11600
self.progress("Grabbing load")
11601
self.set_rc(9, 2000)
11602
self.wait_text("Gripper load grabb", check_context=True)
11603
self.context_clear_collection('STATUSTEXT')
11604
self.progress("Releasing load")
11605
self.set_rc(9, 1000)
11606
self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)
11607
self.progress("Grabbing load")
11608
self.set_rc(9, 2000)
11609
self.wait_text("Gripper load grabb", check_context=True)
11610
self.progress("Test gripper with Mavlink cmd")
11611
11612
self.context_collect('STATUSTEXT')
11613
self.progress("Releasing load")
11614
self.run_cmd(
11615
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11616
p1=1,
11617
p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE
11618
)
11619
self.wait_text("Gripper load releas(ed|ing)", check_context=True, regex=True)
11620
self.progress("Grabbing load")
11621
self.run_cmd(
11622
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11623
p1=1,
11624
p2=mavutil.mavlink.GRIPPER_ACTION_GRAB
11625
)
11626
self.wait_text("Gripper load grabb", check_context=True)
11627
11628
self.context_clear_collection('STATUSTEXT')
11629
self.progress("Releasing load")
11630
self.run_cmd_int(
11631
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11632
p1=1,
11633
p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE
11634
)
11635
self.wait_text("Gripper load releas(ed|ing)", regex=True, check_context=True)
11636
11637
self.progress("Grabbing load")
11638
self.run_cmd_int(
11639
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11640
p1=1,
11641
p2=mavutil.mavlink.GRIPPER_ACTION_GRAB
11642
)
11643
self.wait_text("Gripper load grabb", check_context=True)
11644
11645
self.context_pop()
11646
self.reboot_sitl()
11647
11648
def TestLocalHomePosition(self):
11649
"""Test local home position is sent in HOME_POSITION message"""
11650
self.context_push()
11651
self.wait_ready_to_arm()
11652
11653
# set home to a new location
11654
self.mav.mav.command_long_send(1,
11655
1,
11656
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
11657
0,
11658
0,
11659
0,
11660
0,
11661
0,
11662
-35.357466,
11663
149.142589,
11664
630)
11665
11666
# check home after home set
11667
m = self.assert_receive_message("HOME_POSITION", timeout=5)
11668
if abs(m.x) < 10 or abs(m.y) < 10 or abs(m.z) < 10:
11669
raise NotAchievedException("Failed to get local home position: (got=%u, %u, %u)", m.x, m.y, m.z)
11670
else:
11671
self.progress("Received local home position successfully: (got=%f, %f, %f)" %
11672
(m.x, m.y, m.z))
11673
11674
self.context_pop()
11675
self.reboot_sitl()
11676
11677
def install_terrain_handlers_context(self):
11678
'''install a message handler into the current context which will
11679
listen for an fulfill terrain requests from ArduPilot. Will
11680
die if the data is not available - but
11681
self.terrain_in_offline_mode can be set to true in the
11682
constructor to change this behaviour
11683
this should be called at the very top of your test context!
11684
'''
11685
11686
def check_terrain_requests(mav, m):
11687
if m.get_type() != 'TERRAIN_REQUEST':
11688
return
11689
self.progress("Processing TERRAIN_REQUEST (%s)" %
11690
self.dump_message_verbose(m))
11691
# swiped from mav_terrain.py
11692
for bit in range(56):
11693
if m.mask & (1 << bit) == 0:
11694
continue
11695
11696
lat = m.lat * 1.0e-7
11697
lon = m.lon * 1.0e-7
11698
bit_spacing = m.grid_spacing * 4
11699
(lat, lon) = mp_util.gps_offset(lat, lon,
11700
east=bit_spacing * (bit % 8),
11701
north=bit_spacing * (bit // 8))
11702
data = []
11703
for i in range(4*4):
11704
y = i % 4
11705
x = i // 4
11706
(lat2, lon2) = mp_util.gps_offset(lat, lon,
11707
east=m.grid_spacing * y,
11708
north=m.grid_spacing * x)
11709
# if we are in online mode then we'll try to fetch
11710
# from the internet into the cache dir:
11711
for i in range(120):
11712
alt = self.elevationmodel.GetElevation(lat2, lon2)
11713
if alt is not None:
11714
break
11715
if self.terrain_in_offline_mode:
11716
break
11717
self.progress("No elevation data for (%f %f); retry" %
11718
(lat2, lon2))
11719
time.sleep(1)
11720
if alt is None:
11721
# no data - we can't send the packet
11722
raise ValueError("No elevation data for (%f %f)" % (lat2, lon2))
11723
data.append(int(alt))
11724
self.terrain_data_messages_sent += 1
11725
self.mav.mav.terrain_data_send(m.lat,
11726
m.lon,
11727
m.grid_spacing,
11728
bit,
11729
data)
11730
11731
self.install_message_hook_context(check_terrain_requests)
11732
11733
def install_messageprinter_handlers_context(self, messages):
11734
'''monitor incoming messages, print them out'''
11735
def check_messages(mav, m):
11736
if m.get_type() not in messages:
11737
return
11738
self.progress(self.dump_message_verbose(m))
11739
11740
self.install_message_hook_context(check_messages)
11741
11742
def SetpointGlobalPos(self, timeout=100):
11743
"""Test set position message in guided mode."""
11744
# Disable heading and yaw test on rover type
11745
11746
if self.is_rover():
11747
test_alt = True
11748
test_heading = False
11749
test_yaw_rate = False
11750
else:
11751
test_alt = True
11752
test_heading = True
11753
test_yaw_rate = True
11754
11755
self.install_terrain_handlers_context()
11756
11757
self.set_parameter("FS_GCS_ENABLE", 0)
11758
self.change_mode("GUIDED")
11759
self.wait_ready_to_arm()
11760
self.arm_vehicle()
11761
11762
if self.is_copter() or self.is_heli():
11763
self.user_takeoff(alt_min=50)
11764
11765
targetpos = self.mav.location()
11766
wp_accuracy = None
11767
if self.is_copter() or self.is_heli():
11768
wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)
11769
wp_accuracy = wp_accuracy * 0.01 # cm to m
11770
if self.is_plane() or self.is_rover():
11771
wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)
11772
if wp_accuracy is None:
11773
raise ValueError()
11774
11775
def to_alt_frame(alt, mav_frame):
11776
if mav_frame in ["MAV_FRAME_GLOBAL_RELATIVE_ALT",
11777
"MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",
11778
"MAV_FRAME_GLOBAL_TERRAIN_ALT",
11779
"MAV_FRAME_GLOBAL_TERRAIN_ALT_INT"]:
11780
home = self.home_position_as_mav_location()
11781
return alt - home.alt
11782
else:
11783
return alt
11784
11785
def send_target_position(lat, lng, alt, mav_frame):
11786
self.mav.mav.set_position_target_global_int_send(
11787
0, # timestamp
11788
self.sysid_thismav(), # target system_id
11789
1, # target component id
11790
mav_frame,
11791
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11792
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11793
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11794
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11795
int(lat * 1.0e7), # lat
11796
int(lng * 1.0e7), # lon
11797
alt, # alt
11798
0, # vx
11799
0, # vy
11800
0, # vz
11801
0, # afx
11802
0, # afy
11803
0, # afz
11804
0, # yaw
11805
0, # yawrate
11806
)
11807
11808
def testpos(self, targetpos: mavutil.location, test_alt: bool, frame_name: str, frame):
11809
send_target_position(targetpos.lat, targetpos.lng, to_alt_frame(targetpos.alt, frame_name), frame)
11810
self.wait_location(
11811
targetpos,
11812
accuracy=wp_accuracy,
11813
timeout=timeout,
11814
height_accuracy=(2 if test_alt else None),
11815
minimum_duration=2,
11816
)
11817
11818
for frame in MAV_FRAMES_TO_TEST:
11819
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
11820
self.start_subtest("Testing Set Position in %s" % frame_name)
11821
self.start_subtest("Changing Latitude")
11822
targetpos.lat += 0.0001
11823
if test_alt:
11824
targetpos.alt += 5
11825
testpos(self, targetpos, test_alt, frame_name, frame)
11826
11827
self.start_subtest("Changing Longitude")
11828
targetpos.lng += 0.0001
11829
if test_alt:
11830
targetpos.alt -= 5
11831
testpos(self, targetpos, test_alt, frame_name, frame)
11832
11833
self.start_subtest("Revert Latitude")
11834
targetpos.lat -= 0.0001
11835
if test_alt:
11836
targetpos.alt += 5
11837
testpos(self, targetpos, test_alt, frame_name, frame)
11838
11839
self.start_subtest("Revert Longitude")
11840
targetpos.lng -= 0.0001
11841
if test_alt:
11842
targetpos.alt -= 5
11843
testpos(self, targetpos, test_alt, frame_name, frame)
11844
11845
if test_heading:
11846
self.start_subtest("Testing Yaw targeting in %s" % frame_name)
11847
self.progress("Changing Latitude and Heading")
11848
targetpos.lat += 0.0001
11849
if test_alt:
11850
targetpos.alt += 5
11851
self.mav.mav.set_position_target_global_int_send(
11852
0, # timestamp
11853
self.sysid_thismav(), # target system_id
11854
1, # target component id
11855
frame,
11856
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11857
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11858
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11859
int(targetpos.lat * 1.0e7), # lat
11860
int(targetpos.lng * 1.0e7), # lon
11861
to_alt_frame(targetpos.alt, frame_name), # alt
11862
0, # vx
11863
0, # vy
11864
0, # vz
11865
0, # afx
11866
0, # afy
11867
0, # afz
11868
math.radians(42), # yaw
11869
0, # yawrate
11870
)
11871
self.wait_location(
11872
targetpos,
11873
accuracy=wp_accuracy,
11874
timeout=timeout,
11875
height_accuracy=(2 if test_alt else None),
11876
minimum_duration=2,
11877
)
11878
self.wait_heading(42, minimum_duration=5, timeout=timeout)
11879
11880
self.start_subtest("Revert Latitude and Heading")
11881
targetpos.lat -= 0.0001
11882
if test_alt:
11883
targetpos.alt -= 5
11884
self.mav.mav.set_position_target_global_int_send(
11885
0, # timestamp
11886
self.sysid_thismav(), # target system_id
11887
1, # target component id
11888
frame,
11889
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11890
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11891
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11892
int(targetpos.lat * 1.0e7), # lat
11893
int(targetpos.lng * 1.0e7), # lon
11894
to_alt_frame(targetpos.alt, frame_name), # alt
11895
0, # vx
11896
0, # vy
11897
0, # vz
11898
0, # afx
11899
0, # afy
11900
0, # afz
11901
math.radians(0), # yaw
11902
0, # yawrate
11903
)
11904
self.wait_location(
11905
targetpos,
11906
accuracy=wp_accuracy,
11907
timeout=timeout,
11908
height_accuracy=(2 if test_alt else None),
11909
minimum_duration=2,
11910
)
11911
self.wait_heading(0, minimum_duration=5, timeout=timeout)
11912
11913
if test_yaw_rate:
11914
self.start_subtest("Testing Yaw Rate targeting in %s" % frame_name)
11915
11916
def send_yaw_rate(rate, target=None):
11917
self.mav.mav.set_position_target_global_int_send(
11918
0, # timestamp
11919
self.sysid_thismav(), # target system_id
11920
1, # target component id
11921
frame,
11922
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11923
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11924
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
11925
int(targetpos.lat * 1.0e7), # lat
11926
int(targetpos.lng * 1.0e7), # lon
11927
to_alt_frame(targetpos.alt, frame_name), # alt
11928
0, # vx
11929
0, # vy
11930
0, # vz
11931
0, # afx
11932
0, # afy
11933
0, # afz
11934
0, # yaw
11935
rate, # yawrate in rad/s
11936
)
11937
11938
self.start_subtest("Changing Latitude and Yaw rate")
11939
target_rate = 1.0 # in rad/s
11940
targetpos.lat += 0.0001
11941
if test_alt:
11942
targetpos.alt += 5
11943
self.wait_yaw_speed(target_rate, timeout=timeout,
11944
called_function=lambda plop, empty: send_yaw_rate(
11945
target_rate, None), minimum_duration=5)
11946
self.wait_location(
11947
targetpos,
11948
accuracy=wp_accuracy,
11949
timeout=timeout,
11950
height_accuracy=(2 if test_alt else None),
11951
)
11952
11953
self.start_subtest("Revert Latitude and invert Yaw rate")
11954
target_rate = -1.0
11955
targetpos.lat -= 0.0001
11956
if test_alt:
11957
targetpos.alt -= 5
11958
self.wait_yaw_speed(target_rate, timeout=timeout,
11959
called_function=lambda plop, empty: send_yaw_rate(
11960
target_rate, None), minimum_duration=5)
11961
self.wait_location(
11962
targetpos,
11963
accuracy=wp_accuracy,
11964
timeout=timeout,
11965
height_accuracy=(2 if test_alt else None),
11966
)
11967
self.start_subtest("Changing Yaw rate to zero")
11968
target_rate = 0.0
11969
self.wait_yaw_speed(target_rate, timeout=timeout,
11970
called_function=lambda plop, empty: send_yaw_rate(
11971
target_rate, None), minimum_duration=5)
11972
11973
self.progress("Getting back to home and disarm")
11974
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
11975
self.disarm_vehicle()
11976
11977
def SetpointBadVel(self, timeout=30):
11978
'''try feeding in a very, very bad velocity and make sure it is ignored'''
11979
self.takeoff(mode='GUIDED')
11980
# following values from a real log:
11981
target_speed = Vector3(-3.6019095525029597e+30,
11982
1.7796490496925177e-41,
11983
3.0557017120313744e-26)
11984
11985
self.progress("Feeding in bad global data, hoping we don't move")
11986
11987
def send_speed_vector_global_int(vector , mav_frame):
11988
self.mav.mav.set_position_target_global_int_send(
11989
0, # timestamp
11990
self.sysid_thismav(), # target system_id
11991
1, # target component id
11992
mav_frame,
11993
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11994
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11995
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11996
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11997
0,
11998
0,
11999
0,
12000
vector.x, # vx
12001
vector.y, # vy
12002
vector.z, # vz
12003
0, # afx
12004
0, # afy
12005
0, # afz
12006
0, # yaw
12007
0, # yawrate
12008
)
12009
self.wait_speed_vector(
12010
Vector3(0, 0, 0),
12011
timeout=timeout,
12012
called_function=lambda plop, empty: send_speed_vector_global_int(target_speed, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT), # noqa
12013
minimum_duration=10
12014
)
12015
12016
self.progress("Feeding in bad local data, hoping we don't move")
12017
12018
def send_speed_vector_local_ned(vector , mav_frame):
12019
self.mav.mav.set_position_target_local_ned_send(
12020
0, # timestamp
12021
self.sysid_thismav(), # target system_id
12022
1, # target component id
12023
mav_frame,
12024
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12025
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12026
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
12027
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
12028
0,
12029
0,
12030
0,
12031
vector.x, # vx
12032
vector.y, # vy
12033
vector.z, # vz
12034
0, # afx
12035
0, # afy
12036
0, # afz
12037
0, # yaw
12038
0, # yawrate
12039
)
12040
self.wait_speed_vector(
12041
Vector3(0, 0, 0),
12042
timeout=timeout,
12043
called_function=lambda plop, empty: send_speed_vector_local_ned(target_speed, mavutil.mavlink.MAV_FRAME_LOCAL_NED), # noqa
12044
minimum_duration=10
12045
)
12046
12047
self.do_RTL()
12048
12049
def SetpointGlobalVel(self, timeout=30):
12050
"""Test set position message in guided mode."""
12051
# Disable heading and yaw rate test on rover type
12052
if self.is_rover():
12053
test_vz = False
12054
test_heading = False
12055
test_yaw_rate = False
12056
else:
12057
test_vz = True
12058
test_heading = True
12059
test_yaw_rate = True
12060
12061
self.install_terrain_handlers_context()
12062
12063
self.set_parameter("FS_GCS_ENABLE", 0)
12064
self.change_mode("GUIDED")
12065
self.wait_ready_to_arm()
12066
self.arm_vehicle()
12067
12068
if self.is_copter() or self.is_heli():
12069
self.user_takeoff(alt_min=50)
12070
12071
target_speed = Vector3(1.0, 0.0, 0.0)
12072
12073
wp_accuracy = None
12074
if self.is_copter() or self.is_heli():
12075
wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)
12076
wp_accuracy = wp_accuracy * 0.01 # cm to m
12077
if self.is_plane() or self.is_rover():
12078
wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)
12079
if wp_accuracy is None:
12080
raise ValueError()
12081
12082
def send_speed_vector(vector, mav_frame):
12083
self.mav.mav.set_position_target_global_int_send(
12084
0, # timestamp
12085
self.sysid_thismav(), # target system_id
12086
1, # target component id
12087
mav_frame,
12088
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12089
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12090
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
12091
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
12092
0,
12093
0,
12094
0,
12095
vector.x, # vx
12096
vector.y, # vy
12097
vector.z, # vz
12098
0, # afx
12099
0, # afy
12100
0, # afz
12101
0, # yaw
12102
0, # yawrate
12103
)
12104
12105
for frame in MAV_FRAMES_TO_TEST:
12106
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
12107
self.start_subtest("Testing Set Velocity in %s" % frame_name)
12108
self.progress("Changing Vx speed")
12109
self.wait_speed_vector(
12110
target_speed,
12111
timeout=timeout,
12112
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12113
minimum_duration=2
12114
)
12115
12116
self.start_subtest("Add Vy speed")
12117
target_speed.y = 1.0
12118
self.wait_speed_vector(
12119
target_speed,
12120
timeout=timeout,
12121
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12122
minimum_duration=2)
12123
12124
self.start_subtest("Add Vz speed")
12125
if test_vz:
12126
target_speed.z = 1.0
12127
else:
12128
target_speed.z = 0.0
12129
self.wait_speed_vector(
12130
target_speed,
12131
timeout=timeout,
12132
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12133
minimum_duration=2
12134
)
12135
12136
self.start_subtest("Invert Vz speed")
12137
if test_vz:
12138
target_speed.z = -1.0
12139
else:
12140
target_speed.z = 0.0
12141
self.wait_speed_vector(
12142
target_speed,
12143
timeout=timeout,
12144
called_function=lambda plop, empty: send_speed_vector(target_speed, frame), minimum_duration=2
12145
)
12146
12147
self.start_subtest("Invert Vx speed")
12148
target_speed.x = -1.0
12149
self.wait_speed_vector(
12150
target_speed,
12151
timeout=timeout,
12152
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12153
minimum_duration=2
12154
)
12155
12156
self.start_subtest("Invert Vy speed")
12157
target_speed.y = -1.0
12158
self.wait_speed_vector(
12159
target_speed,
12160
timeout=timeout,
12161
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12162
minimum_duration=2
12163
)
12164
12165
self.start_subtest("Set Speed to zero")
12166
target_speed.x = 0.0
12167
target_speed.y = 0.0
12168
target_speed.z = 0.0
12169
self.wait_speed_vector(
12170
target_speed,
12171
timeout=timeout,
12172
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
12173
minimum_duration=2
12174
)
12175
12176
if test_heading:
12177
self.start_subtest("Testing Yaw targeting in %s" % frame_name)
12178
12179
def send_yaw_target(yaw, mav_frame):
12180
self.mav.mav.set_position_target_global_int_send(
12181
0, # timestamp
12182
self.sysid_thismav(), # target system_id
12183
1, # target component id
12184
mav_frame,
12185
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12186
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12187
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
12188
0,
12189
0,
12190
0,
12191
0, # vx
12192
0, # vy
12193
0, # vz
12194
0, # afx
12195
0, # afy
12196
0, # afz
12197
math.radians(yaw), # yaw
12198
0, # yawrate
12199
)
12200
12201
target_speed.x = 1.0
12202
target_speed.y = 1.0
12203
if test_vz:
12204
target_speed.z = -1.0
12205
else:
12206
target_speed.z = 0.0
12207
12208
def send_yaw_target_vel(yaw, vector, mav_frame):
12209
self.mav.mav.set_position_target_global_int_send(
12210
0, # timestamp
12211
self.sysid_thismav(), # target system_id
12212
1, # target component id
12213
mav_frame,
12214
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12215
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12216
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
12217
0,
12218
0,
12219
0,
12220
vector.x, # vx
12221
vector.y, # vy
12222
vector.z, # vz
12223
0, # afx
12224
0, # afy
12225
0, # afz
12226
math.radians(yaw), # yaw
12227
0, # yawrate
12228
)
12229
12230
self.start_subtest("Target a fixed Heading")
12231
target_yaw = 42.0
12232
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
12233
called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))
12234
12235
self.start_subtest("Set target Heading")
12236
target_yaw = 0.0
12237
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
12238
called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))
12239
12240
self.start_subtest("Add Vx, Vy, Vz speed and target a fixed Heading")
12241
target_yaw = 42.0
12242
self.wait_heading(
12243
target_yaw,
12244
minimum_duration=5,
12245
timeout=timeout,
12246
called_function=lambda p, e: send_yaw_target_vel(target_yaw,
12247
target_speed,
12248
frame)
12249
)
12250
self.wait_speed_vector(
12251
target_speed,
12252
called_function=lambda p, e: send_yaw_target_vel(target_yaw,
12253
target_speed,
12254
frame)
12255
)
12256
12257
self.start_subtest("Stop Vx, Vy, Vz speed and target zero Heading")
12258
target_yaw = 0.0
12259
target_speed.x = 0.0
12260
target_speed.y = 0.0
12261
target_speed.z = 0.0
12262
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
12263
called_function=lambda plop, empty: send_yaw_target_vel(target_yaw, target_speed, frame))
12264
self.wait_speed_vector(
12265
target_speed,
12266
timeout=timeout,
12267
called_function=lambda p, ee: send_yaw_target_vel(target_yaw,
12268
target_speed,
12269
frame),
12270
minimum_duration=2
12271
)
12272
12273
if test_yaw_rate:
12274
self.start_subtest("Testing Yaw Rate targeting in %s" % frame_name)
12275
12276
def send_yaw_rate(rate, mav_frame):
12277
self.mav.mav.set_position_target_global_int_send(
12278
0, # timestamp
12279
self.sysid_thismav(), # target system_id
12280
1, # target component id
12281
mav_frame,
12282
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12283
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12284
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
12285
0,
12286
0,
12287
0,
12288
0, # vx
12289
0, # vy
12290
0, # vz
12291
0, # afx
12292
0, # afy
12293
0, # afz
12294
0, # yaw
12295
rate, # yawrate in rad/s
12296
)
12297
12298
target_speed.x = 1.0
12299
target_speed.y = 1.0
12300
if test_vz:
12301
target_speed.z = -1.0
12302
else:
12303
target_speed.z = 0.0
12304
12305
def send_yaw_rate_vel(rate, vector, mav_frame):
12306
self.mav.mav.set_position_target_global_int_send(
12307
0, # timestamp
12308
self.sysid_thismav(), # target system_id
12309
1, # target component id
12310
mav_frame,
12311
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
12312
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
12313
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
12314
0,
12315
0,
12316
0,
12317
vector.x, # vx
12318
vector.y, # vy
12319
vector.z, # vz
12320
0, # afx
12321
0, # afy
12322
0, # afz
12323
0, # yaw
12324
rate, # yawrate in rad/s
12325
)
12326
12327
self.start_subtest("Set Yaw rate")
12328
target_rate = 1.0
12329
self.wait_yaw_speed(target_rate, timeout=timeout,
12330
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
12331
12332
self.start_subtest("Invert Yaw rate")
12333
target_rate = -1.0
12334
self.wait_yaw_speed(target_rate, timeout=timeout,
12335
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
12336
12337
self.start_subtest("Stop Yaw rate")
12338
target_rate = 0.0
12339
self.wait_yaw_speed(target_rate, timeout=timeout,
12340
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
12341
12342
self.start_subtest("Set Yaw Rate and Vx, Vy, Vz speed")
12343
target_rate = 1.0
12344
self.wait_yaw_speed(
12345
target_rate,
12346
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12347
target_speed,
12348
frame),
12349
minimum_duration=2
12350
)
12351
self.wait_speed_vector(
12352
target_speed,
12353
timeout=timeout,
12354
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12355
target_speed,
12356
frame),
12357
minimum_duration=2
12358
)
12359
12360
target_rate = -1.0
12361
target_speed.x = -1.0
12362
target_speed.y = -1.0
12363
if test_vz:
12364
target_speed.z = 1.0
12365
else:
12366
target_speed.z = 0.0
12367
self.start_subtest("Invert Vx, Vy, Vz speed")
12368
self.wait_yaw_speed(
12369
target_rate,
12370
timeout=timeout,
12371
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12372
target_speed,
12373
frame),
12374
minimum_duration=2
12375
)
12376
self.wait_speed_vector(
12377
target_speed,
12378
timeout=timeout,
12379
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12380
target_speed,
12381
frame),
12382
minimum_duration=2
12383
)
12384
12385
target_rate = 0.0
12386
target_speed.x = 0.0
12387
target_speed.y = 0.0
12388
target_speed.z = 0.0
12389
self.start_subtest("Stop Yaw rate and all speed")
12390
self.wait_yaw_speed(
12391
target_rate,
12392
timeout=timeout,
12393
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12394
target_speed,
12395
frame),
12396
minimum_duration=2
12397
)
12398
self.wait_speed_vector(
12399
target_speed,
12400
timeout=timeout,
12401
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12402
target_speed,
12403
frame),
12404
minimum_duration=2
12405
)
12406
12407
self.progress("Getting back to home and disarm")
12408
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
12409
self.disarm_vehicle()
12410
12411
def is_blimp(self):
12412
return False
12413
12414
def is_copter(self):
12415
return False
12416
12417
def is_sub(self):
12418
return False
12419
12420
def is_plane(self):
12421
return False
12422
12423
def is_rover(self):
12424
return False
12425
12426
def is_balancebot(self):
12427
return False
12428
12429
def is_heli(self):
12430
return False
12431
12432
def is_tracker(self):
12433
return False
12434
12435
def initial_mode(self):
12436
'''return mode vehicle should start in with no RC inputs set'''
12437
return None
12438
12439
def initial_mode_switch_mode(self):
12440
'''return mode vehicle should start in with default RC inputs set'''
12441
return None
12442
12443
def upload_fences_from_locations(self, fences, target_system=1, target_component=1):
12444
seq = 0
12445
items = []
12446
12447
for (vertex_type, locs) in fences:
12448
if isinstance(locs, dict):
12449
# circular fence
12450
item = self.mav.mav.mission_item_int_encode(
12451
target_system,
12452
target_component,
12453
seq, # seq
12454
mavutil.mavlink.MAV_FRAME_GLOBAL,
12455
vertex_type,
12456
0, # current
12457
0, # autocontinue
12458
locs["radius"], # p1
12459
0, # p2
12460
0, # p3
12461
0, # p4
12462
int(locs["loc"].lat * 1e7), # latitude
12463
int(locs["loc"].lng * 1e7), # longitude
12464
33.0000, # altitude
12465
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
12466
seq += 1
12467
items.append(item)
12468
continue
12469
count = len(locs)
12470
for loc in locs:
12471
item = self.mav.mav.mission_item_int_encode(
12472
target_system,
12473
target_component,
12474
seq, # seq
12475
mavutil.mavlink.MAV_FRAME_GLOBAL,
12476
vertex_type,
12477
0, # current
12478
0, # autocontinue
12479
count, # p1
12480
0, # p2
12481
0, # p3
12482
0, # p4
12483
int(loc.lat * 1e7), # latitude
12484
int(loc.lng * 1e7), # longitude
12485
33.0000, # altitude
12486
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
12487
seq += 1
12488
items.append(item)
12489
12490
self.check_fence_upload_download(items)
12491
12492
def rally_MISSION_ITEM_INT_from_loc(self, loc):
12493
return self.create_MISSION_ITEM_INT(
12494
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
12495
x=int(loc.lat*1e7),
12496
y=int(loc.lng*1e7),
12497
z=loc.alt,
12498
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
12499
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY
12500
)
12501
12502
def upload_rally_points_from_locations(self, rally_point_locs):
12503
'''takes a sequence of locations, sets vehicle rally points to those locations'''
12504
items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs]
12505
self.correct_wp_seq_numbers(items)
12506
self.check_rally_upload_download(items)
12507
12508
def wait_for_initial_mode(self):
12509
'''wait until we get a heartbeat with an expected initial mode (the
12510
one specified in the vehicle constructor)'''
12511
want = self.initial_mode()
12512
if want is None:
12513
return
12514
self.progress("Waiting for initial mode %s" % want)
12515
self.wait_mode(want)
12516
12517
def wait_for_mode_switch_poll(self):
12518
'''look for a transition from boot-up-mode (e.g. the flightmode
12519
specified in Copter's constructor) to the one specified by the mode
12520
switch value'''
12521
want = self.initial_mode_switch_mode()
12522
if want is None:
12523
return
12524
self.progress("Waiting for mode-switch mode %s" % want)
12525
self.wait_mode(want)
12526
12527
def start_subtest(self, description):
12528
self.progress("-")
12529
self.progress("---------- %s ----------" % description)
12530
self.progress("-")
12531
12532
def start_subsubtest(self, description):
12533
self.progress(".")
12534
self.progress(".......... %s .........." % description)
12535
self.progress(".")
12536
12537
def end_subtest(self, description):
12538
'''TODO: sanity checks?'''
12539
pass
12540
12541
def end_subsubtest(self, description):
12542
'''TODO: sanity checks?'''
12543
pass
12544
12545
def last_onboard_log(self):
12546
'''return number of last onboard log'''
12547
mavproxy = self.start_mavproxy()
12548
mavproxy.send("module load log\n")
12549
loaded_module = False
12550
mavproxy.expect(["Loaded module log", "module log already loaded"])
12551
if mavproxy.match.group(0) == "Loaded module log":
12552
loaded_module = True
12553
mavproxy.send("log list\n")
12554
mavproxy.expect(["lastLog ([0-9]+)", "No logs"])
12555
if mavproxy.match.group(0) == "No logs":
12556
num_log = None
12557
else:
12558
num_log = int(mavproxy.match.group(1))
12559
if loaded_module:
12560
mavproxy.send("module unload log\n")
12561
mavproxy.expect("Unloaded module log")
12562
self.stop_mavproxy(mavproxy)
12563
return num_log
12564
12565
def current_onboard_log_number(self):
12566
logs = self.download_full_log_list(print_logs=False)
12567
return sorted(logs.keys())[-1]
12568
12569
def current_onboard_log_filepath(self):
12570
'''return filepath to currently open dataflash log. We assume that's
12571
the latest log...'''
12572
logs = self.log_list()
12573
latest = logs[-1]
12574
return latest
12575
12576
def dfreader_for_path(self, path):
12577
return DFReader.DFReader_binary(path,
12578
zero_time_base=True)
12579
12580
def dfreader_for_current_onboard_log(self):
12581
return self.dfreader_for_path(self.current_onboard_log_filepath())
12582
12583
def current_onboard_log_contains_message(self, messagetype):
12584
self.progress("Checking (%s) for (%s)" %
12585
(self.current_onboard_log_filepath(), messagetype))
12586
dfreader = self.dfreader_for_current_onboard_log()
12587
m = dfreader.recv_match(type=messagetype)
12588
print("m=%s" % str(m))
12589
return m is not None
12590
12591
def assert_current_onboard_log_contains_message(self, messagetype):
12592
if not self.current_onboard_log_contains_message(messagetype):
12593
raise NotAchievedException("Current onboard log does not contain message %s" % messagetype)
12594
12595
def run_tests(self, tests) -> List[Result]:
12596
"""Autotest vehicle in SITL."""
12597
if self.run_tests_called:
12598
raise ValueError("run_tests called twice")
12599
self.run_tests_called = True
12600
12601
result_list = []
12602
12603
try:
12604
self.init()
12605
12606
self.progress("Waiting for a heartbeat with mavlink protocol %s"
12607
% self.mav.WIRE_PROTOCOL_VERSION)
12608
self.wait_heartbeat()
12609
self.wait_for_initial_mode()
12610
self.progress("Setting up RC parameters")
12611
self.set_rc_default()
12612
self.wait_for_mode_switch_poll()
12613
if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling
12614
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
12615
12616
for test in tests:
12617
self.drain_mav_unparsed()
12618
result_list.append(self.run_one_test(test))
12619
12620
except pexpect.TIMEOUT:
12621
self.progress("Failed with timeout")
12622
result = Result(test)
12623
result.passed = False
12624
result.reason = "Failed with timeout"
12625
result_list.append(result)
12626
if self.logs_dir:
12627
if glob.glob("core*") or glob.glob("ap-*.core"):
12628
self.check_logs("FRAMEWORK")
12629
12630
if self.rc_thread is not None:
12631
self.progress("Joining RC thread")
12632
self.rc_thread_should_quit = True
12633
self.rc_thread.join()
12634
self.rc_thread = None
12635
12636
if self.mav is not None:
12637
self.mav.close()
12638
self.mav = None
12639
12640
self.stop_SITL()
12641
12642
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
12643
model=self.frame)
12644
files = glob.glob("*" + valgrind_log)
12645
valgrind_failed = False
12646
for valgrind_log in files:
12647
os.chmod(valgrind_log, 0o644)
12648
if os.path.getsize(valgrind_log) > 0:
12649
target = self.buildlogs_path("%s-%s" % (
12650
self.log_name(),
12651
os.path.basename(valgrind_log)))
12652
self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target))
12653
shutil.move(valgrind_log, target)
12654
valgrind_failed = True
12655
if valgrind_failed:
12656
result_list.append(ValgrindFailedResult())
12657
12658
return result_list
12659
12660
def dictdiff(self, dict1, dict2):
12661
fred = copy.copy(dict1)
12662
for key in dict2.keys():
12663
try:
12664
del fred[key]
12665
except KeyError:
12666
pass
12667
return fred
12668
12669
# download parameters tries to cope with its download being
12670
# interrupted or broken by simply retrying the download a few
12671
# times.
12672
def download_parameters(self, target_system, target_component):
12673
# try a simple fetch-all:
12674
last_parameter_received = 0
12675
attempt_count = 0
12676
start_done = False
12677
# make flake8 happy:
12678
count = 0
12679
expected_count = 0
12680
seen_ids = {}
12681
self.progress("Downloading parameters")
12682
debug = False
12683
while True:
12684
now = self.get_sim_time_cached()
12685
if not start_done or now - last_parameter_received > 10:
12686
start_done = True
12687
if attempt_count > 3:
12688
raise AutoTestTimeoutException("Failed to download parameters (have %s/%s) (seen_ids-count=%u)" %
12689
(str(count), str(expected_count), len(seen_ids.keys())))
12690
elif attempt_count != 0:
12691
self.progress("Download failed; retrying")
12692
self.delay_sim_time(1)
12693
debug = True
12694
self.drain_mav()
12695
self.mav.mav.param_request_list_send(target_system, target_component)
12696
attempt_count += 1
12697
count = 0
12698
expected_count = None
12699
seen_ids = {}
12700
id_seq = {}
12701
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=10)
12702
if m is None:
12703
raise AutoTestTimeoutException("tardy PARAM_VALUE (have %s/%s)" % (
12704
str(count), str(expected_count)))
12705
if m.param_index == 65535:
12706
self.progress("volunteered parameter: %s" % str(m))
12707
continue
12708
if debug:
12709
self.progress(" received id=%4u param_count=%4u %s=%f" %
12710
(m.param_index, m.param_count, m.param_id, m.param_value))
12711
if m.param_index >= m.param_count:
12712
raise ValueError("parameter index (%u) gte parameter count (%u)" %
12713
(m.param_index, m.param_count))
12714
if expected_count is None:
12715
expected_count = m.param_count
12716
else:
12717
if m.param_count != expected_count:
12718
raise ValueError("expected count changed")
12719
if m.param_id not in seen_ids:
12720
count += 1
12721
seen_ids[m.param_id] = m.param_value
12722
last_parameter_received = now
12723
if count == expected_count:
12724
break
12725
12726
self.progress("Downloaded %u parameters OK (attempt=%u)" %
12727
(count, attempt_count))
12728
return (seen_ids, id_seq)
12729
12730
def test_parameters_download(self):
12731
self.start_subtest("parameter download")
12732
target_system = self.sysid_thismav()
12733
target_component = 1
12734
self.progress("First Download:")
12735
(parameters, seq_id) = self.download_parameters(target_system, target_component)
12736
self.reboot_sitl()
12737
self.progress("Second download:")
12738
(parameters2, seq2_id) = self.download_parameters(target_system, target_component)
12739
12740
delta = self.dictdiff(parameters, parameters2)
12741
if len(delta) != 0:
12742
raise ValueError("Got %u fewer parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %
12743
(len(delta), len(parameters), len(parameters2), str(delta.keys())))
12744
12745
delta = self.dictdiff(parameters2, parameters)
12746
if len(delta) != 0:
12747
raise ValueError("Got %u extra parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %
12748
(len(delta), len(parameters), len(parameters2), str(delta.keys())))
12749
12750
self.end_subsubtest("parameter download")
12751
12752
def test_enable_parameter(self):
12753
self.start_subtest("enable parameters")
12754
target_system = 1
12755
target_component = 1
12756
parameters = self.download_parameters(target_system, target_component)
12757
enable_parameter = self.sample_enable_parameter()
12758
if enable_parameter is None:
12759
self.progress("Skipping enable parameter check as no enable parameter supplied")
12760
return
12761
self.set_parameter(enable_parameter, 1)
12762
parameters2 = self.download_parameters(target_system, target_component)
12763
if len(parameters) == len(parameters2):
12764
raise NotAchievedException("Enable parameter did not increase no of parameters downloaded")
12765
self.end_subsubtest("enable download")
12766
12767
def test_parameters_mis_total(self):
12768
self.start_subsubtest("parameter mis_total")
12769
if self.is_tracker():
12770
# uses CMD_TOTAL not MIS_TOTAL, and it's in a scalr not a
12771
# group and it's generally all bad.
12772
return
12773
self.start_subtest("Ensure GCS is not able to set MIS_TOTAL")
12774
old_mt = self.get_parameter("MIS_TOTAL", attempts=20) # retries to avoid seeming race condition with MAVProxy
12775
ex = None
12776
try:
12777
self.set_parameter("MIS_TOTAL", 17, attempts=1)
12778
except ValueError as e:
12779
ex = e
12780
if ex is None:
12781
raise NotAchievedException("Set parameter when I shouldn't have")
12782
if old_mt != self.get_parameter("MIS_TOTAL"):
12783
raise NotAchievedException("Total has changed")
12784
12785
self.start_subtest("Ensure GCS is able to set other MIS_ parameters")
12786
self.set_parameter("MIS_OPTIONS", 1)
12787
if self.get_parameter("MIS_OPTIONS") != 1:
12788
raise NotAchievedException("Failed to set MIS_OPTIONS")
12789
12790
mavproxy = self.start_mavproxy()
12791
from_mavproxy = self.get_parameter_mavproxy(mavproxy, "MIS_OPTIONS")
12792
if from_mavproxy != 1:
12793
raise NotAchievedException("MAVProxy failed to get parameter")
12794
self.stop_mavproxy(mavproxy)
12795
12796
def test_parameter_documentation(self):
12797
'''ensure parameter documentation is valid'''
12798
self.start_subsubtest("Check all parameters are documented")
12799
self.test_parameter_documentation_get_all_parameters()
12800
12801
def Parameters(self):
12802
'''general small tests for parameter system'''
12803
if self.is_balancebot():
12804
# same binary and parameters as Rover
12805
return
12806
self.test_parameter_documentation()
12807
self.test_parameters_mis_total()
12808
self.test_parameters_download()
12809
12810
def disabled_tests(self):
12811
return {}
12812
12813
def test_parameter_checks_poscontrol(self, param_prefix):
12814
self.wait_ready_to_arm()
12815
self.context_push()
12816
self.set_parameter("%s_NE_POS_P" % param_prefix, -1)
12817
self.run_cmd(
12818
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
12819
p1=1, # ARM
12820
timeout=4,
12821
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
12822
)
12823
self.context_pop()
12824
self.run_cmd(
12825
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
12826
p1=1, # ARM
12827
timeout=4,
12828
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
12829
)
12830
self.disarm_vehicle()
12831
12832
def assert_not_receiving_message(self, message, timeout=1, mav=None):
12833
self.progress("making sure we're not getting %s messages" % message)
12834
if mav is None:
12835
mav = self.mav
12836
m = mav.recv_match(type=message, blocking=True, timeout=timeout)
12837
if m is not None:
12838
raise PreconditionFailedException("Receiving %s messages" % message)
12839
12840
def PIDTuning(self):
12841
'''Test PID Tuning'''
12842
self.assert_not_receiving_message('PID_TUNING', timeout=5)
12843
self.set_parameter("GCS_PID_MASK", 1)
12844
self.progress("making sure we are now getting PID_TUNING messages")
12845
self.assert_receive_message('PID_TUNING', timeout=5)
12846
12847
def sample_mission_filename(self):
12848
return "flaps.txt"
12849
12850
def AdvancedFailsafe(self):
12851
'''Test Advanced Failsafe'''
12852
ex = None
12853
try:
12854
self.drain_mav()
12855
if self.is_plane(): # other vehicles can always terminate
12856
self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
12857
self.set_parameters({
12858
"AFS_ENABLE": 1,
12859
"MAV_GCS_SYSID": self.mav.source_system,
12860
"RTL_AUTOLAND": 2,
12861
})
12862
self.drain_mav()
12863
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
12864
self.set_parameter("AFS_TERM_ACTION", 42)
12865
self.load_sample_mission()
12866
self.context_collect("STATUSTEXT")
12867
self.change_mode("AUTO") # must go to auto for AFS to latch on
12868
self.wait_statustext("AFS State: AFS_AUTO", check_context=True)
12869
if self.is_plane():
12870
self.change_mode("MANUAL")
12871
elif self.is_copter():
12872
self.change_mode("STABILIZE")
12873
12874
self.start_subtest("RC Failure")
12875
self.context_push()
12876
self.context_collect("STATUSTEXT")
12877
self.set_parameters({
12878
"AFS_RC_FAIL_TIME": 1,
12879
"SIM_RC_FAIL": 1,
12880
})
12881
self.wait_statustext("Terminating due to RC failure", check_context=True)
12882
self.context_pop()
12883
self.set_parameter("AFS_TERMINATE", 0)
12884
12885
if not self.is_plane():
12886
# plane requires a polygon fence...
12887
self.start_subtest("Altitude Limit breach")
12888
self.set_parameters({
12889
"AFS_AMSL_LIMIT": 100,
12890
"AFS_QNH_PRESSURE": 1015.2,
12891
})
12892
self.do_fence_enable()
12893
self.wait_statustext("Terminating due to fence breach", check_context=True)
12894
self.set_parameter("AFS_AMSL_LIMIT", 0)
12895
self.set_parameter("AFS_TERMINATE", 0)
12896
self.do_fence_disable()
12897
12898
self.start_subtest("GPS Failure")
12899
self.wait_ready_to_arm()
12900
self.context_push()
12901
self.context_collect("STATUSTEXT")
12902
self.set_parameters({
12903
"AFS_MAX_GPS_LOSS": 1,
12904
"SIM_GPS1_ENABLE": 0,
12905
})
12906
self.wait_statustext("AFS State: GPS_LOSS", check_context=True)
12907
self.context_pop()
12908
self.set_parameter("AFS_TERMINATE", 0)
12909
12910
self.start_subtest("GCS Request")
12911
self.context_push()
12912
self.context_collect("STATUSTEXT")
12913
self.run_cmd(
12914
mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,
12915
p1=1, # terminate
12916
)
12917
self.wait_statustext("Terminating due to GCS request", check_context=True)
12918
self.context_pop()
12919
self.set_parameter("AFS_TERMINATE", 0)
12920
12921
except Exception as e:
12922
ex = e
12923
try:
12924
self.do_fence_disable()
12925
except ValueError:
12926
# may not actually be enabled....
12927
pass
12928
if ex is not None:
12929
raise ex
12930
12931
def AdvancedFailsafeBadBaro(self):
12932
'''ensure GPS can be used as a fallback in case of baro dying'''
12933
self.set_parameters({
12934
"AFS_ENABLE": 1,
12935
"MAV_GCS_SYSID": self.mav.source_system,
12936
"AFS_AMSL_LIMIT": 1000,
12937
"AFS_QNH_PRESSURE": 1000,
12938
"AFS_AMSL_ERR_GPS": 10,
12939
})
12940
self.wait_ready_to_arm()
12941
self.start_subtest("Ensuring breaking baros doesn't terminate")
12942
self.set_parameters({
12943
"SIM_BARO_DISABLE": 1,
12944
"SIM_BAR2_DISABLE": 1,
12945
})
12946
self.delay_sim_time(10)
12947
self.start_subtest("Ensuring breaking GPS does now terminate")
12948
self.set_parameters({
12949
"SIM_GPS1_ENABLE": 0,
12950
})
12951
self.wait_statustext("Terminating due to fence breach")
12952
12953
def drain_mav_seconds(self, seconds):
12954
tstart = self.get_sim_time_cached()
12955
while self.get_sim_time_cached() - tstart < seconds:
12956
self.drain_mav()
12957
self.delay_sim_time(0.5)
12958
12959
def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT", verbose=False):
12960
tstart = self.get_sim_time()
12961
while True:
12962
now = self.get_sim_time_cached()
12963
if now - tstart > timeout:
12964
raise AutoTestTimeoutException("Did not get good GPS lock")
12965
m = self.mav.recv_match(type=message_type, blocking=True, timeout=0.1)
12966
if verbose:
12967
self.progress("Received: %s" % str(m))
12968
if m is None:
12969
continue
12970
if m.fix_type >= fix_type:
12971
break
12972
12973
def NMEAOutput(self):
12974
'''Test AHRS NMEA Output can be read by out NMEA GPS'''
12975
self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output
12976
self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA
12977
port = self.spare_network_port()
12978
self.customise_SITL_commandline([
12979
"--serial4=tcp:%u" % port, # GPS2 is NMEA....
12980
"--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port
12981
])
12982
self.do_timesync_roundtrip()
12983
self.wait_gps_fix_type_gte(3)
12984
gps1 = self.assert_receive_message("GPS_RAW_INT", timeout=10, verbose=True)
12985
tstart = self.get_sim_time()
12986
while True:
12987
now = self.get_sim_time_cached()
12988
if now - tstart > 20:
12989
raise NotAchievedException("NMEA output not updating?!")
12990
gps2 = self.mav.recv_match(type="GPS2_RAW", blocking=True, timeout=1)
12991
self.progress("gps2=%s" % str(gps2))
12992
if gps2 is None:
12993
continue
12994
if gps2.time_usec != 0:
12995
break
12996
max_distance = 1
12997
distance = self.get_distance_int(gps1, gps2)
12998
if distance > max_distance:
12999
raise NotAchievedException("NMEA output inaccurate (dist=%f want<%f)" %
13000
(distance, max_distance))
13001
13002
def mavproxy_load_module(self, mavproxy, module):
13003
mavproxy.send("module load %s\n" % module)
13004
mavproxy.expect("Loaded module %s" % module)
13005
13006
def mavproxy_unload_module(self, mavproxy, module):
13007
mavproxy.send("module unload %s\n" % module)
13008
mavproxy.expect("Unloaded module %s" % module)
13009
13010
def AccelCal(self):
13011
'''Accelerometer Calibration testing'''
13012
ex = None
13013
mavproxy = self.start_mavproxy()
13014
try:
13015
# setup with pre-existing accel offsets, to show that existing offsets don't
13016
# adversely affect a new cal
13017
pre_aofs = [Vector3(2.8, 1.2, 1.7),
13018
Vector3(0.2, -0.9, 2.9)]
13019
pre_ascale = [Vector3(0.95, 1.2, 0.98),
13020
Vector3(1.1, 1.0, 0.93)]
13021
aofs = [Vector3(0.7, -0.3, 1.8),
13022
Vector3(-2.1, 1.9, 2.3)]
13023
ascale = [Vector3(0.98, 1.12, 1.05),
13024
Vector3(1.11, 0.98, 0.96)]
13025
atrim = Vector3(0.05, -0.03, 0)
13026
pre_atrim = Vector3(-0.02, 0.04, 0)
13027
param_map = [("INS_ACCOFFS", "SIM_ACC1_BIAS", pre_aofs[0], aofs[0]),
13028
("INS_ACC2OFFS", "SIM_ACC2_BIAS", pre_aofs[1], aofs[1]),
13029
("INS_ACCSCAL", "SIM_ACC1_SCAL", pre_ascale[0], ascale[0]),
13030
("INS_ACC2SCAL", "SIM_ACC2_SCAL", pre_ascale[1], ascale[1]),
13031
("AHRS_TRIM", "SIM_ACC_TRIM", pre_atrim, atrim)]
13032
axes = ['X', 'Y', 'Z']
13033
13034
# form the pre-calibration params
13035
initial_params = {}
13036
for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:
13037
for axis in axes:
13038
initial_params[ins_prefix + "_" + axis] = getattr(pre_value, axis.lower())
13039
initial_params[sim_prefix + "_" + axis] = getattr(post_value, axis.lower())
13040
self.set_parameters(initial_params)
13041
self.customise_SITL_commandline(["-M", "calibration"])
13042
self.mavproxy_load_module(mavproxy, "sitl_calibration")
13043
self.mavproxy_load_module(mavproxy, "calibration")
13044
self.mavproxy_load_module(mavproxy, "relay")
13045
mavproxy.send("sitl_accelcal\n")
13046
mavproxy.send("accelcal\n")
13047
mavproxy.expect("Calibrated")
13048
for wanted in [
13049
"level",
13050
"on its LEFT side",
13051
"on its RIGHT side",
13052
"nose DOWN",
13053
"nose UP",
13054
"on its BACK",
13055
]:
13056
timeout = 2
13057
mavproxy.expect("Place vehicle %s and press any key." % wanted, timeout=timeout)
13058
mavproxy.expect("sitl_accelcal: sending attitude, please wait..", timeout=timeout)
13059
mavproxy.expect("sitl_accelcal: attitude detected, please press any key..", timeout=timeout)
13060
mavproxy.send("\n")
13061
mavproxy.expect(".*Calibration successful", timeout=timeout)
13062
self.drain_mav()
13063
13064
self.progress("Checking results")
13065
accuracy_pct = 0.5
13066
for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:
13067
for axis in axes:
13068
pname = ins_prefix+"_"+axis
13069
v = self.get_parameter(pname)
13070
expected_v = getattr(post_value, axis.lower())
13071
if v == expected_v:
13072
continue
13073
error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)
13074
if error_pct > accuracy_pct:
13075
raise NotAchievedException(
13076
"Incorrect value %.6f for %s should be %.6f error %.2f%%" %
13077
(v, pname, expected_v, error_pct))
13078
else:
13079
self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct))
13080
except Exception as e:
13081
self.print_exception_caught(e)
13082
ex = e
13083
self.mavproxy_unload_module(mavproxy, "relay")
13084
self.mavproxy_unload_module(mavproxy, "calibration")
13085
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
13086
self.stop_mavproxy(mavproxy)
13087
if ex is not None:
13088
raise ex
13089
13090
def ahrstrim_preflight_cal(self):
13091
# setup with non-zero accel offsets
13092
self.set_parameters({
13093
"INS_ACCOFFS_X": 0.7,
13094
"INS_ACCOFFS_Y": -0.3,
13095
"INS_ACCOFFS_Z": 1.8,
13096
"INS_ACC2OFFS_X": -2.1,
13097
"INS_ACC2OFFS_Y": 1.9,
13098
"INS_ACC2OFFS_Z": 2.3,
13099
"SIM_ACC1_BIAS_X": 0.7,
13100
"SIM_ACC1_BIAS_Y": -0.3,
13101
"SIM_ACC1_BIAS_Z": 1.8,
13102
"SIM_ACC2_BIAS_X": -2.1,
13103
"SIM_ACC2_BIAS_Y": 1.9,
13104
"SIM_ACC2_BIAS_Z": 2.3,
13105
"AHRS_TRIM_X": 0.05,
13106
"AHRS_TRIM_Y": -0.03,
13107
"SIM_ACC_TRIM_X": -0.04,
13108
"SIM_ACC_TRIM_Y": 0.05,
13109
})
13110
expected_parms = {
13111
"AHRS_TRIM_X": -0.04,
13112
"AHRS_TRIM_Y": 0.05,
13113
}
13114
13115
self.progress("Starting ahrstrim")
13116
self.drain_mav()
13117
self.mav.mav.command_long_send(self.sysid_thismav(), 1,
13118
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
13119
0, 0, 0, 0, 2, 0, 0)
13120
self.wait_statustext('Trim OK')
13121
self.drain_mav()
13122
13123
self.progress("Checking results")
13124
accuracy_pct = 0.2
13125
for (pname, expected_v) in expected_parms.items():
13126
v = self.get_parameter(pname)
13127
if v == expected_v:
13128
continue
13129
error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)
13130
if error_pct > accuracy_pct:
13131
raise NotAchievedException(
13132
"Incorrect value %.6f for %s should be %.6f error %.2f%%" %
13133
(v, pname, expected_v, error_pct))
13134
self.progress("Correct value %.4f for %s error %.2f%%" %
13135
(v, pname, error_pct))
13136
13137
def user_takeoff(self, alt_min=30, timeout=30, max_err=5):
13138
'''takeoff using mavlink takeoff command'''
13139
self.run_cmd(
13140
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
13141
p7=alt_min, # param7
13142
)
13143
self.wait_altitude(alt_min - 1,
13144
(alt_min + max_err),
13145
relative=True,
13146
timeout=timeout)
13147
13148
def ahrstrim_attitude_correctness(self):
13149
self.wait_ready_to_arm()
13150
HOME = self.sitl_start_location()
13151
for heading in 0, 90:
13152
self.customise_SITL_commandline([
13153
"--home", "%s,%s,%s,%s" % (HOME.lat, HOME.lng, HOME.alt, heading)
13154
])
13155
for ahrs_type in [0, 2, 3, 11]:
13156
self.start_subsubtest("Testing AHRS_TYPE=%u" % ahrs_type)
13157
self.context_push()
13158
13159
# Special setup for ExternalAHRS (type 11)
13160
if ahrs_type == 11:
13161
# Test all simulated ExternalAHRS backends
13162
external_ahrs_configs = [
13163
{
13164
"name": "VectorNav",
13165
"device": "VectorNav",
13166
"eahrs_type": 1,
13167
},
13168
{
13169
"name": "MicroStrain5",
13170
"device": "MicroStrain5",
13171
"eahrs_type": 2,
13172
},
13173
{
13174
"name": "InertialLabs",
13175
"device": "ILabs",
13176
"eahrs_type": 5,
13177
},
13178
{
13179
"name": "MicroStrain7",
13180
"device": "MicroStrain7",
13181
"eahrs_type": 7,
13182
},
13183
]
13184
13185
for config in external_ahrs_configs:
13186
self.start_subsubtest("Testing ExternalAHRS backend: %s" % config["name"])
13187
self.context_push()
13188
13189
self.customise_SITL_commandline([
13190
"--serial4=sim:%s" % config["device"],
13191
])
13192
self.set_parameters({
13193
"EAHRS_TYPE": config["eahrs_type"],
13194
"SERIAL4_PROTOCOL": 36, # ExternalAHRS protocol
13195
"SERIAL4_BAUD": 230400,
13196
"GPS1_TYPE": 21, # External AHRS
13197
"AHRS_EKF_TYPE": ahrs_type,
13198
"INS_GYR_CAL": 1,
13199
"EAHRS_SENSORS": 0xD, # GPS|BARO|COMPASS (exclude IMU)
13200
})
13201
self.reboot_sitl()
13202
self.delay_sim_time(5)
13203
self.progress("Running accelcal")
13204
self.run_cmd(
13205
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
13206
p5=4,
13207
timeout=5,
13208
)
13209
self.wait_prearm_sys_status_healthy(timeout=120)
13210
13211
for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:
13212
self.set_parameters({
13213
'AHRS_TRIM_X': math.radians(r),
13214
'AHRS_TRIM_Y': math.radians(p),
13215
"SIM_ACC_TRIM_X": math.radians(r),
13216
"SIM_ACC_TRIM_Y": math.radians(p),
13217
})
13218
self.reboot_sitl()
13219
self.context_set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SIM_STATE, 10)
13220
att_desroll = 0
13221
att_despitch = 0
13222
if ahrs_type == 11:
13223
# this is very nasty compatibility
13224
# code for the fact our rotations are
13225
# incorrect for ExternalAHRS eulers
13226
# and rotation matrix! It is here to
13227
# ensure behaviour is preserved until
13228
# we can fix the bug! Search for
13229
# "note that this is suspect" to find
13230
# the problem code.
13231
att_desroll = -r
13232
att_despitch = -p
13233
self.wait_attitude(desroll=att_desroll, despitch=att_despitch, timeout=120, tolerance=1.5)
13234
if ahrs_type != 0:
13235
self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)
13236
self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)
13237
self.wait_attitude(desroll=0, despitch=0, message_type='SIM_STATE', tolerance=1, timeout=120)
13238
13239
self.context_pop()
13240
self.reboot_sitl()
13241
13242
# Skip the normal test loop for ahrs_type 11 since we already tested it above
13243
self.context_pop()
13244
continue
13245
else:
13246
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
13247
self.reboot_sitl()
13248
self.wait_prearm_sys_status_healthy(timeout=120)
13249
for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:
13250
self.set_parameters({
13251
'AHRS_TRIM_X': math.radians(r),
13252
'AHRS_TRIM_Y': math.radians(p),
13253
"SIM_ACC_TRIM_X": math.radians(r),
13254
"SIM_ACC_TRIM_Y": math.radians(p),
13255
})
13256
self.reboot_sitl()
13257
self.context_set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SIM_STATE, 10)
13258
self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5)
13259
self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5, message_type='SIM_STATE')
13260
if ahrs_type != 0: # we don't get secondary msgs while DCM is primary
13261
self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)
13262
self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)
13263
self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120, message_type='SIM_STATE')
13264
13265
self.context_pop()
13266
self.reboot_sitl()
13267
13268
def AHRSTrim(self):
13269
'''AHRS trim testing'''
13270
self.start_subtest("Attitude Correctness")
13271
self.ahrstrim_attitude_correctness()
13272
self.delay_sim_time(5)
13273
self.start_subtest("Preflight Calibration")
13274
self.ahrstrim_preflight_cal()
13275
13276
def Button(self):
13277
'''Test Buttons'''
13278
self.set_parameter("SIM_PIN_MASK", 0)
13279
self.set_parameter("BTN_ENABLE", 1)
13280
self.drain_mav()
13281
self.do_heartbeats(force=True)
13282
btn = 4
13283
pin = 3
13284
self.set_parameter("BTN_PIN%u" % btn, pin, verbose=True)
13285
m = self.assert_not_receive_message('BUTTON_CHANGE')
13286
mask = 1 << pin
13287
self.set_parameter("SIM_PIN_MASK", mask)
13288
m = self.assert_receive_message('BUTTON_CHANGE', verbose=True)
13289
if not (m.state & mask):
13290
raise NotAchievedException("Bit not set in mask (got=%u want=%u)" % (m.state, mask))
13291
m2 = self.assert_receive_message('BUTTON_CHANGE', timeout=10)
13292
self.progress("### m2: %s" % str(m2))
13293
# wait for messages to stop coming:
13294
self.drain_mav_seconds(15)
13295
13296
new_mask = 0
13297
self.send_set_parameter("SIM_PIN_MASK", new_mask, verbose=True)
13298
m3 = self.assert_receive_message('BUTTON_CHANGE')
13299
self.progress("### m3: %s" % str(m3))
13300
13301
if m.last_change_ms == m3.last_change_ms:
13302
raise NotAchievedException("last_change_ms same as first message")
13303
if m3.state != new_mask:
13304
raise NotAchievedException("Unexpected mask (want=%u got=%u)" %
13305
(new_mask, m3.state))
13306
self.progress("correct BUTTON_CHANGE event received")
13307
13308
if self.is_tracker():
13309
# tracker starts armed, which is annoying
13310
self.progress("Skipping arm/disarm tests for tracker")
13311
return
13312
13313
self.context_push()
13314
self.wait_ready_to_arm()
13315
self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM
13316
self.set_parameter("SIM_PIN_MASK", mask)
13317
self.wait_armed()
13318
self.set_parameter("SIM_PIN_MASK", 0)
13319
self.wait_disarmed()
13320
self.context_pop()
13321
13322
if self.is_rover():
13323
self.context_push()
13324
# arming should be inhibited while e-STOP is in use:
13325
# set the function:
13326
self.set_parameter("BTN_FUNC%u" % btn, 31)
13327
# invert the sense of the pin, so eStop is asserted when pin is low:
13328
self.set_parameter("BTN_OPTIONS%u" % btn, 1 << 1)
13329
self.reboot_sitl()
13330
# assert the pin:
13331
self.set_parameter("SIM_PIN_MASK", mask)
13332
self.wait_ready_to_arm()
13333
self.arm_vehicle()
13334
self.disarm_vehicle()
13335
# de-assert the pin:
13336
self.set_parameter("SIM_PIN_MASK", 0)
13337
self.delay_sim_time(1) # 5Hz update rate on Button library
13338
self.context_collect("STATUSTEXT")
13339
# try to arm the vehicle:
13340
self.run_cmd(
13341
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
13342
p1=1, # ARM
13343
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
13344
)
13345
self.assert_prearm_failure("Motors Emergency Stopped",
13346
other_prearm_failures_fatal=False)
13347
self.reboot_sitl()
13348
self.assert_prearm_failure(
13349
"Motors Emergency Stopped",
13350
other_prearm_failures_fatal=False)
13351
self.context_pop()
13352
self.reboot_sitl()
13353
13354
if self.is_rover():
13355
self.start_subtest("Testing using buttons for changing modes")
13356
self.context_push()
13357
if not self.mode_is('MANUAL'):
13358
raise NotAchievedException("Bad mode")
13359
self.set_parameter("BTN_FUNC%u" % btn, 53) # steering mode
13360
# press button:
13361
self.set_parameter("SIM_PIN_MASK", mask)
13362
self.wait_mode('STEERING')
13363
# release button:
13364
self.set_parameter("SIM_PIN_MASK", 0)
13365
self.wait_mode('MANUAL')
13366
self.context_pop()
13367
13368
def compare_number_percent(self, num1, num2, percent):
13369
if num1 == 0 and num2 == 0:
13370
return True
13371
if abs(num1 - num2) / max(abs(num1), abs(num2)) <= percent * 0.01:
13372
return True
13373
return False
13374
13375
def bit_extract(self, number, offset, length):
13376
mask = 0
13377
for i in range(offset, offset+length):
13378
mask |= 1 << i
13379
return (number & mask) >> offset
13380
13381
def tf_encode_gps_latitude(self, lat):
13382
value = 0
13383
if lat < 0:
13384
value = ((abs(lat)//100)*6) | 0x40000000
13385
else:
13386
value = ((abs(lat)//100)*6)
13387
return value
13388
13389
def tf_validate_gps(self, value): # shared by proto 4 and proto 10
13390
self.progress("validating gps (0x%02x)" % value)
13391
lat = value
13392
gri = self.assert_receive_message('GPS_RAW_INT')
13393
gri_lat = self.tf_encode_gps_latitude(gri.lat)
13394
self.progress("GLOBAL_POSITION_INT lat==%f frsky==%f" % (gri_lat, lat))
13395
if gri_lat == lat:
13396
return True
13397
return False
13398
13399
def tfp_prep_number(self, number, digits, power):
13400
res = 0
13401
abs_number = abs(number)
13402
if digits == 2 and power == 1: # number encoded on 8 bits: 7 bits for digits + 1 for 10^power
13403
if abs_number < 100:
13404
res = abs_number << 1
13405
elif abs_number < 1270:
13406
res = (round(abs_number * 0.1) << 1) | 0x1
13407
else: # transmit max possible value (0x7F x 10^1 = 1270)
13408
res = 0xFF
13409
if number < 0: # if number is negative, add sign bit in front
13410
res |= 0x1 << 8
13411
elif digits == 2 and power == 2: # number encoded on 9 bits: 7 bits for digits + 2 for 10^power
13412
if abs_number < 100:
13413
res = abs_number << 2
13414
elif abs_number < 1000:
13415
res = (round(abs_number * 0.1) << 2) | 0x1
13416
elif abs_number < 10000:
13417
res = (round(abs_number * 0.01) << 2) | 0x2
13418
elif abs_number < 127000:
13419
res = (round(abs_number * 0.001) << 2) | 0x3
13420
else: # transmit max possible value (0x7F x 10^3 = 127000)
13421
res = 0x1FF
13422
if number < 0: # if number is negative, add sign bit in front
13423
res |= 0x1 << 9
13424
elif digits == 3 and power == 1: # number encoded on 11 bits: 10 bits for digits + 1 for 10^power
13425
if abs_number < 1000:
13426
res = abs_number << 1
13427
elif abs_number < 10240:
13428
res = (round(abs_number * 0.1) << 1) | 0x1
13429
else: # transmit max possible value (0x3FF x 10^1 = 10240)
13430
res = 0x7FF
13431
if number < 0: # if number is negative, add sign bit in front
13432
res |= 0x1 << 11
13433
elif digits == 3 and power == 2: # number encoded on 12 bits: 10 bits for digits + 2 for 10^power
13434
if abs_number < 1000:
13435
res = abs_number << 2
13436
elif abs_number < 10000:
13437
res = (round(abs_number * 0.1) << 2) | 0x1
13438
elif abs_number < 100000:
13439
res = (round(abs_number * 0.01) << 2) | 0x2
13440
elif abs_number < 1024000:
13441
res = (round(abs_number * 0.001) << 2) | 0x3
13442
else: # transmit max possible value (0x3FF x 10^3 = 127000)
13443
res = 0xFFF
13444
if number < 0: # if number is negative, add sign bit in front
13445
res |= 0x1 << 12
13446
return res
13447
13448
def tfp_validate_ap_status(self, value): # 0x5001
13449
self.progress("validating ap_status(0x%02x)" % value)
13450
flight_mode = self.bit_extract(value, 0, 5) - 1 # first mode is 1 not 0 :-)
13451
# simple_mode = self.bit_extract(value, 5, 2)
13452
# is_flying = not self.bit_extract(value, 7, 1)
13453
# status_armed = self.bit_extract(value, 8, 1)
13454
# batt_failsafe = self.bit_extract(value, 9, 1)
13455
# ekf_failsafe = self.bit_extract(value, 10, 2)
13456
# imu_temp = self.bit_extract(value, 26, 6) + 19 # IMU temperature: 0 means temp =< 19, 63 means temp => 82
13457
heartbeat = self.wait_heartbeat()
13458
mav_flight_mode = heartbeat.custom_mode
13459
self.progress(" mode=%u heartbeat=%u" % (flight_mode, mav_flight_mode))
13460
if mav_flight_mode == flight_mode:
13461
self.progress("flight mode match")
13462
return True
13463
# FIXME: need to check other values as well
13464
return False
13465
13466
def tfp_validate_attitude(self, value):
13467
self.progress("validating attitude(0x%02x)" % value)
13468
roll = (min(self.bit_extract(value, 0, 11), 1800) - 900) * 0.2 # roll [0,1800] ==> [-180,180]
13469
pitch = (min(self.bit_extract(value, 11, 10), 900) - 450) * 0.2 # pitch [0,900] ==> [-90,90]
13470
# rng_cm = self.bit_extract(value, 22, 10) * (10 ^ self.bit_extract(value, 21, 1)) # cm
13471
atti = self.assert_receive_message('ATTITUDE')
13472
atti_roll = round(atti.roll)
13473
self.progress("ATTITUDE roll==%f frsky==%f" % (atti_roll, roll))
13474
if abs(atti_roll - roll) >= 5:
13475
return False
13476
atti_pitch = round(atti.pitch)
13477
self.progress("ATTITUDE pitch==%f frsky==%f" % (atti_pitch, pitch))
13478
if abs(atti_pitch - pitch) >= 5:
13479
return False
13480
# FIXME: need to check other values as well
13481
return True
13482
13483
def tfp_validate_home_status(self, value):
13484
self.progress("validating home status(0x%02x)" % value)
13485
# home_dist_m = self.bit_extract(value,2,10) * (10^self.bit_extract(value,0,2))
13486
home_alt_dm = self.bit_extract(value, 14, 10) * (10 ^ self.bit_extract(value, 12, 2)) * 0.1 * (self.bit_extract(value, 24, 1) == 1 and -1 or 1) # noqa
13487
# home_angle_d = self.bit_extract(value, 25, 7) * 3
13488
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
13489
gpi_relative_alt_dm = gpi.relative_alt/100.0
13490
self.progress("GLOBAL_POSITION_INT rel_alt==%fm frsky_home_alt==%fm" % (gpi_relative_alt_dm, home_alt_dm))
13491
if abs(gpi_relative_alt_dm - home_alt_dm) < 10:
13492
return True
13493
# FIXME: need to check other values as well
13494
return False
13495
13496
def tfp_validate_gps_status(self, value):
13497
self.progress("validating gps status(0x%02x)" % value)
13498
# num_sats = self.bit_extract(value, 0, 4)
13499
gps_status = self.bit_extract(value, 4, 2) + self.bit_extract(value, 14, 2)
13500
# gps_hdop = self.bit_extract(value, 7, 7) * (10 ^ self.bit_extract(value, 6, 1)) # dm
13501
# gps_alt = self.bit_extract(value, 24, 7) * (10 ^ self.bit_extract(value, 22, 2)) * (self.bit_extract(value, 31, 1) == 1 and -1 or 1) # dm # noqa
13502
gri = self.assert_receive_message('GPS_RAW_INT')
13503
gri_status = gri.fix_type
13504
self.progress("GPS_RAW_INT fix_type==%f frsky==%f" % (gri_status, gps_status))
13505
if gps_status == gri_status:
13506
return True
13507
# FIXME: need to check other values as well
13508
return False
13509
13510
def tfp_validate_vel_and_yaw(self, value): # 0x5005
13511
self.progress("validating vel_and_yaw(0x%02x)" % value)
13512
z_vel_dm_per_second = self.bit_extract(value, 1, 7) * (10 ^ self.bit_extract(value, 0, 1)) * (self.bit_extract(value, 8, 1) == 1 and -1 or 1) # noqa
13513
xy_vel = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))
13514
yaw = self.bit_extract(value, 17, 11) * 0.2
13515
gpi = self.mav.recv_match(
13516
type='GLOBAL_POSITION_INT',
13517
blocking=True,
13518
timeout=1
13519
)
13520
if gpi is None:
13521
return
13522
self.progress(" yaw=%u gpi=%u" % (yaw, gpi.hdg*0.01))
13523
self.progress(" xy_vel=%u" % xy_vel)
13524
self.progress(" z_vel_dm_per_second=%u" % z_vel_dm_per_second)
13525
if self.compare_number_percent(gpi.hdg*0.01, yaw, 10):
13526
self.progress("Yaw match")
13527
return True
13528
# FIXME: need to be under way to check the velocities, really....
13529
return False
13530
13531
def tfp_validate_battery1(self, value):
13532
self.progress("validating battery1 (0x%02x)" % value)
13533
voltage = self.bit_extract(value, 0, 9) # dV
13534
# current = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))
13535
# mah = self.bit_extract(value, 17, 15)
13536
voltage = value * 0.1
13537
batt = self.assert_receive_message(
13538
'BATTERY_STATUS',
13539
timeout=5,
13540
condition="BATTERY_STATUS.id==0"
13541
)
13542
battery_status_value = batt.voltages[0]*0.001
13543
self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_value, voltage))
13544
if abs(battery_status_value - voltage) > 0.1:
13545
return False
13546
# FIXME: need to check other values as well
13547
return True
13548
13549
def tfp_validate_params(self, value):
13550
param_id = self.bit_extract(value, 24, 4)
13551
param_value = self.bit_extract(value, 0, 24)
13552
self.progress("received param (0x%02x) (id=%u value=%u)" %
13553
(value, param_id, param_value))
13554
frame_type = param_value
13555
hb = self.mav.messages['HEARTBEAT']
13556
hb_type = hb.type
13557
self.progress("validate_params: HEARTBEAT type==%f frsky==%f param_id=%u" % (hb_type, frame_type, param_id))
13558
if param_id != 1:
13559
return False
13560
if hb_type == frame_type:
13561
return True
13562
# FIXME: need to check other values as well
13563
return False
13564
13565
def tfp_validate_rpm(self, value):
13566
self.progress("validating rpm (0x%02x)" % value)
13567
tf_rpm = self.bit_extract(value, 0, 16)
13568
rpm = self.assert_receive_message(type='RPM', timeout=5)
13569
rpm_value = round(rpm.rpm1 * 0.1)
13570
self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tf_rpm))
13571
if rpm_value != tf_rpm:
13572
return False
13573
return True
13574
13575
def tfp_validate_terrain(self, value):
13576
self.progress("validating terrain(0x%02x)" % value)
13577
alt_above_terrain_dm = self.bit_extract(value, 2, 10) * (10 ^ self.bit_extract(value, 0, 2)) * 0.1 * (self.bit_extract(value, 12, 1) == 1 and -1 or 1) # noqa
13578
terrain = self.assert_receive_message('TERRAIN_REPORT')
13579
altitude_terrain_dm = round(terrain.current_height*10)
13580
self.progress("TERRAIN_REPORT terrain_alt==%fdm frsky_terrain_alt==%fdm" % (altitude_terrain_dm, alt_above_terrain_dm))
13581
if abs(altitude_terrain_dm - alt_above_terrain_dm) < 1:
13582
return True
13583
return False
13584
13585
def tfp_validate_wind(self, value):
13586
self.progress("validating wind(0x%02x)" % value)
13587
speed_m = self.bit_extract(value, 8, 7) * (10 ^ self.bit_extract(value, 7, 1)) * 0.1 # speed in m/s
13588
wind = self.assert_receive_message('WIND')
13589
self.progress("WIND mav==%f frsky==%f" % (speed_m, wind.speed))
13590
if abs(speed_m - wind.speed) < 0.5:
13591
return True
13592
return False
13593
13594
def test_frsky_passthrough_do_wants(self, frsky, wants):
13595
13596
tstart = self.get_sim_time_cached()
13597
while len(wants):
13598
self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))
13599
wants_copy = copy.copy(wants)
13600
self.drain_mav()
13601
t2 = self.get_sim_time_cached()
13602
if t2 - tstart > 300:
13603
self.progress("Failed to get frsky passthrough data")
13604
self.progress("Counts of sensor_id polls sent:")
13605
frsky.dump_sensor_id_poll_counts_as_progress_messages()
13606
self.progress("Counts of dataids received:")
13607
frsky.dump_dataid_counts_as_progress_messages()
13608
raise AutoTestTimeoutException("Failed to get frsky passthrough data")
13609
frsky.update()
13610
for want in wants_copy:
13611
data = frsky.get_data(want)
13612
if data is None:
13613
continue
13614
self.progress("Checking 0x%x" % (want,))
13615
if wants[want](data):
13616
self.progress(" Fulfilled")
13617
del wants[want]
13618
13619
def FRSkyPassThroughStatustext(self):
13620
'''test FRSKy protocol's telem-passthrough functionality'''
13621
# we disable terrain here as RCTelemetry can queue a lot of
13622
# statustexts if terrain tiles aren't available which can
13623
# happen on the autotest server.
13624
self.set_parameters({
13625
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
13626
"RPM1_TYPE": 10, # enable RPM output
13627
"TERRAIN_ENABLE": 0,
13628
})
13629
port = self.spare_network_port()
13630
self.customise_SITL_commandline([
13631
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13632
])
13633
frsky = FRSkyPassThrough(("127.0.0.1", port),
13634
get_time=self.get_sim_time_cached)
13635
13636
# waiting until we are ready to arm should ensure our wanted
13637
# statustext doesn't get blatted out of the ArduPilot queue by
13638
# random messages.
13639
self.wait_ready_to_arm()
13640
13641
# test we get statustext strings. This relies on ArduPilot
13642
# emitting statustext strings when we fetch parameters. (or,
13643
# now, an updating-barometer statustext)
13644
tstart = self.get_sim_time()
13645
old_data = None
13646
text = ""
13647
13648
self.context_collect('STATUSTEXT')
13649
command = mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION
13650
self.send_cmd(
13651
command,
13652
p3=1, # p3, baro
13653
)
13654
# this is a test for asynchronous handling of mavlink messages:
13655
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_IN_PROGRESS, 2)
13656
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_ACCEPTED, 5)
13657
13658
received_frsky_texts = []
13659
last_len_received_statustexts = 0
13660
timeout = 7 * self.speedup # it can take a *long* time to get these messages down!
13661
while True:
13662
self.drain_mav()
13663
now = self.get_sim_time_cached()
13664
if now - tstart > timeout:
13665
raise NotAchievedException("Did not get statustext in time")
13666
frsky.update()
13667
data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats.
13668
if data is None:
13669
continue
13670
# frsky sends each quartet three times; skip the suplicates.
13671
if old_data is not None and old_data == data:
13672
continue
13673
old_data = data
13674
self.progress("Got (0x%x)" % data)
13675
severity = 0
13676
last = False
13677
for i in 3, 2, 1, 0:
13678
x = (data >> i*8) & 0xff
13679
text += chr(x & 0x7f)
13680
self.progress(" x=0x%02x" % x)
13681
if x & 0x80:
13682
severity += 1 << i
13683
self.progress("Text sev=%u: %s" % (severity, str(text)))
13684
if (x & 0x7f) == 0x00:
13685
last = True
13686
if last:
13687
m = None
13688
text = text.rstrip("\0")
13689
self.progress("Received frsky text (%s)" % (text,))
13690
self.progress("context texts: %s" %
13691
str([st.text for st in self.context_collection('STATUSTEXT')]))
13692
m = self.statustext_in_collections(text)
13693
if m is not None:
13694
want_sev = m.severity
13695
if severity != want_sev:
13696
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
13697
self.progress("Got statustext (%s)" % m.text)
13698
break
13699
received_frsky_texts.append((severity, text))
13700
text = ""
13701
received_statustexts = self.context_collection('STATUSTEXT')
13702
if len(received_statustexts) != last_len_received_statustexts:
13703
last_len_received_statustexts = len(received_statustexts)
13704
self.progress("received statustexts: %s" % str([st.text for st in received_statustexts]))
13705
self.progress("received frsky texts: %s" % str(received_frsky_texts))
13706
for (want_sev, received_text) in received_frsky_texts:
13707
for m in received_statustexts:
13708
if m.text == received_text:
13709
if want_sev != m.severity:
13710
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
13711
self.progress("Got statustext (%s)" % received_text)
13712
break
13713
13714
def FRSkyPassThroughSensorIDs(self):
13715
'''test FRSKy protocol's telem-passthrough functionality (sensor IDs)'''
13716
self.set_parameters({
13717
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
13718
"RPM1_TYPE": 10, # enable RPM output
13719
})
13720
port = self.spare_network_port()
13721
self.customise_SITL_commandline([
13722
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13723
])
13724
frsky = FRSkyPassThrough(("127.0.0.1", port),
13725
get_time=self.get_sim_time_cached)
13726
13727
self.wait_ready_to_arm()
13728
13729
# we need to start the engine to get some RPM readings, we do it for plane only
13730
# anything with a lambda in here needs a proper test written.
13731
# This, at least makes sure we're getting some of each
13732
# message. These are ordered according to the wfq scheduler
13733
wants = {
13734
0x5000: lambda xx: True,
13735
0x5006: self.tfp_validate_attitude,
13736
0x0800: self.tf_validate_gps,
13737
0x5005: self.tfp_validate_vel_and_yaw,
13738
0x5001: self.tfp_validate_ap_status,
13739
0x5002: self.tfp_validate_gps_status,
13740
0x5004: self.tfp_validate_home_status,
13741
# 0x5008: lambda x : True, # no second battery, so this doesn't arrive
13742
0x5003: self.tfp_validate_battery1,
13743
0x5007: self.tfp_validate_params,
13744
0x500B: self.tfp_validate_terrain,
13745
0x500C: self.tfp_validate_wind,
13746
}
13747
self.test_frsky_passthrough_do_wants(frsky, wants)
13748
13749
# now check RPM:
13750
if self.is_plane():
13751
self.set_autodisarm_delay(0)
13752
if not self.arm_vehicle():
13753
raise NotAchievedException("Failed to ARM")
13754
self.set_rc(3, 1050)
13755
wants = {
13756
0x500A: self.tfp_validate_rpm,
13757
}
13758
self.test_frsky_passthrough_do_wants(frsky, wants)
13759
self.zero_throttle()
13760
self.progress("Wait for vehicle to slow down")
13761
self.wait_groundspeed(0, 0.3)
13762
self.disarm_vehicle()
13763
13764
self.progress("Counts of sensor_id polls sent:")
13765
frsky.dump_sensor_id_poll_counts_as_progress_messages()
13766
self.progress("Counts of dataids received:")
13767
frsky.dump_dataid_counts_as_progress_messages()
13768
13769
def decode_mavlite_param_value(self, message):
13770
'''returns a tuple of parameter name, value'''
13771
(value,) = struct.unpack("<f", message[0:4])
13772
name = message[4:]
13773
return (name, value)
13774
13775
def decode_mavlite_command_ack(self, message):
13776
'''returns a tuple of parameter name, value'''
13777
(command, result) = struct.unpack("<HB", message)
13778
return (command, result)
13779
13780
def read_message_via_mavlite(self, frsky, sport_to_mavlite):
13781
'''read bytes from frsky mavlite stream, trying to form up a mavlite
13782
message'''
13783
tstart = self.get_sim_time()
13784
timeout = 30 * self.speedup/10.0
13785
if self.valgrind or self.callgrind:
13786
timeout *= 10
13787
while True:
13788
self.drain_mav(quiet=True)
13789
tnow = self.get_sim_time_cached()
13790
if tnow - tstart > timeout:
13791
raise NotAchievedException("Did not get parameter via mavlite")
13792
frsky.update()
13793
if sport_to_mavlite.state == sport_to_mavlite.state_MESSAGE_RECEIVED:
13794
message = sport_to_mavlite.get_message()
13795
sport_to_mavlite.reset()
13796
# self.progress("############ message received (type=%u)" % message.msgid)
13797
return message
13798
13799
def read_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):
13800
tstart = self.get_sim_time()
13801
while True:
13802
tnow = self.get_sim_time_cached()
13803
if tnow - tstart > 30 * self.speedup / 10.0:
13804
raise NotAchievedException("Did not get parameter via mavlite")
13805
message = self.read_message_via_mavlite(frsky, sport_to_mavlite)
13806
if message.msgid != mavutil.mavlink.MAVLINK_MSG_ID_PARAM_VALUE:
13807
raise NotAchievedException("Unexpected msgid %u received" % message.msgid)
13808
(got_name, value) = self.decode_mavlite_param_value(message.body)
13809
# self.progress("Received parameter: %s=%f" % (name, value))
13810
got_name = got_name.decode('ascii')
13811
if got_name != name:
13812
raise NotAchievedException("Incorrect name received (want=%s) (got=%s)" % (name, got_name))
13813
return value
13814
13815
def get_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):
13816
# self.progress("########## Sending request")
13817
frsky.send_mavlite_param_request_read(name)
13818
return self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)
13819
13820
def set_parameter_via_mavlite(self, frsky, sport_to_mavlite, name, value):
13821
# self.progress("########## Sending request")
13822
frsky.send_mavlite_param_set(name, value)
13823
# new value is echoed back immediately:
13824
got_val = self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)
13825
if abs(got_val - value) > 0.00001:
13826
raise NotAchievedException("Returned value not same as set value (want=%f got=%f)" % (value, got_val))
13827
13828
def run_cmd_via_mavlite(self,
13829
frsky,
13830
sport_to_mavlite,
13831
command,
13832
p1=None,
13833
p2=None,
13834
p3=None,
13835
p4=None,
13836
p5=None,
13837
p6=None,
13838
p7=None,
13839
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
13840
frsky.send_mavlite_command_long(
13841
command,
13842
p1=p1,
13843
p2=p2,
13844
p3=p3,
13845
p4=p4,
13846
p5=p5,
13847
p6=p6,
13848
p7=p7,
13849
)
13850
self.run_cmd_via_mavlite_get_ack(
13851
frsky,
13852
sport_to_mavlite,
13853
command,
13854
want_result
13855
)
13856
13857
def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_result):
13858
'''expect and read a command-ack from frsky sport passthrough'''
13859
msg = self.read_message_via_mavlite(frsky, sport_to_mavlite)
13860
if msg.msgid != mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_ACK:
13861
raise NotAchievedException("Expected a command-ack, got a %u" % msg.msgid)
13862
(got_command, got_result) = self.decode_mavlite_command_ack(msg.body)
13863
if got_command != command:
13864
raise NotAchievedException(
13865
"Did not receive expected command in command_ack; want=%u got=%u" %
13866
(command, got_command))
13867
if got_result != want_result:
13868
raise NotAchievedException(
13869
"Did not receive expected result in command_ack; want=%u got=%u" %
13870
(want_result, got_result))
13871
13872
def FRSkyMAVlite(self):
13873
'''Test FrSky MAVlite serial output'''
13874
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
13875
port = self.spare_network_port()
13876
self.customise_SITL_commandline([
13877
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13878
])
13879
frsky = FRSkyPassThrough(("127.0.0.1", port))
13880
frsky.connect()
13881
13882
sport_to_mavlite = SPortToMAVlite()
13883
frsky.data_downlink_handler = sport_to_mavlite.downlink_handler
13884
13885
self.start_subtest("Get parameter via MAVlite")
13886
param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles
13887
set_value = 97.21
13888
self.set_parameter(param_name, set_value) # DO NOT FLY
13889
got_value = self.get_parameter_via_mavlite(frsky,
13890
sport_to_mavlite,
13891
param_name)
13892
if abs(got_value - set_value) > 0.00001:
13893
raise NotAchievedException("Incorrect value retrieved via mavlite (want=%f got=%f)" % (set_value, got_value))
13894
self.progress("Got value OK")
13895
self.end_subtest("Get parameter via MAVlite")
13896
13897
self.start_subtest("Set parameter via MAVlite")
13898
param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles
13899
set_value = 91.67
13900
# frsky.verbose = True
13901
self.set_parameter_via_mavlite(frsky, sport_to_mavlite, param_name, set_value) # DO NOT FLY
13902
got_value = self.get_parameter(param_name)
13903
if abs(got_value - set_value) > 0.00001:
13904
raise NotAchievedException("Incorrect value retrieved via mavlink (want=%f got=%f)" % (set_value, got_value))
13905
self.progress("Set value OK")
13906
self.end_subtest("Set parameter via MAVlite")
13907
13908
self.start_subtest("Calibrate Baro via MAVLite")
13909
self.context_push()
13910
self.context_collect("STATUSTEXT")
13911
self.run_cmd_via_mavlite(
13912
frsky,
13913
sport_to_mavlite,
13914
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
13915
p1=0,
13916
p2=0,
13917
p3=1.0,
13918
)
13919
self.wait_statustext("Updating barometer calibration", check_context=True)
13920
self.context_pop()
13921
self.end_subtest("Calibrate Baro via MAVLite")
13922
13923
self.start_subtest("Change mode via MAVLite")
13924
# FIXME: currently plane-specific
13925
self.run_cmd_via_mavlite(
13926
frsky,
13927
sport_to_mavlite,
13928
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
13929
p1=mavutil.mavlink.PLANE_MODE_MANUAL,
13930
)
13931
self.wait_mode("MANUAL")
13932
self.run_cmd_via_mavlite(
13933
frsky,
13934
sport_to_mavlite,
13935
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
13936
p1=mavutil.mavlink.PLANE_MODE_FLY_BY_WIRE_A,
13937
)
13938
self.wait_mode("FBWA")
13939
self.end_subtest("Change mode via MAVLite")
13940
13941
self.start_subtest("Enable fence via MAVlite")
13942
# Fence can be enabled using MAV_CMD
13943
self.run_cmd_via_mavlite(
13944
frsky,
13945
sport_to_mavlite,
13946
mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,
13947
p1=1,
13948
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
13949
)
13950
self.end_subtest("Enable fence via MAVlite")
13951
13952
def tfs_validate_gps_alt(self, value):
13953
self.progress("validating gps altitude (0x%02x)" % value)
13954
alt_m = value * 0.01 # cm -> m
13955
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
13956
if gpi is None:
13957
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
13958
gpi_alt_m = round(gpi.alt * 0.001) # mm-> m
13959
self.progress("GLOBAL_POSITION_INT alt==%f frsky==%f" % (gpi_alt_m, alt_m))
13960
if self.compare_number_percent(gpi_alt_m, alt_m, 10):
13961
return True
13962
return False
13963
13964
def tfs_validate_baro_alt(self, value):
13965
self.progress("validating baro altitude (0x%02x)" % value)
13966
alt_m = value * 0.01 # cm -> m
13967
gpi = self.assert_receive_message('GLOBAL_POSITION_INT')
13968
if gpi is None:
13969
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
13970
gpi_alt_m = round(gpi.relative_alt * 0.001) # mm -> m
13971
self.progress("GLOBAL_POSITION_INT relative_alt==%f frsky==%f" % (gpi_alt_m, alt_m))
13972
if abs(gpi_alt_m - alt_m) < 1:
13973
return True
13974
return False
13975
13976
def tfs_validate_gps_speed(self, value):
13977
self.progress("validating gps speed (0x%02x)" % value)
13978
speed_ms = value * 0.001 # mm/s -> m/s
13979
vfr_hud = self.assert_receive_message('VFR_HUD')
13980
vfr_hud_speed_ms = round(vfr_hud.groundspeed)
13981
self.progress("VFR_HUD groundspeed==%f frsky==%f" % (vfr_hud_speed_ms, speed_ms))
13982
if self.compare_number_percent(vfr_hud_speed_ms, speed_ms, 10):
13983
return True
13984
return False
13985
13986
def tfs_validate_yaw(self, value):
13987
self.progress("validating yaw (0x%02x)" % value)
13988
yaw_deg = value * 0.01 # cd -> deg
13989
vfr_hud = self.assert_receive_message('VFR_HUD')
13990
vfr_hud_yaw_deg = round(vfr_hud.heading)
13991
self.progress("VFR_HUD heading==%f frsky==%f" % (vfr_hud_yaw_deg, yaw_deg))
13992
if self.compare_number_percent(vfr_hud_yaw_deg, yaw_deg, 10):
13993
return True
13994
return False
13995
13996
def tfs_validate_vspeed(self, value):
13997
self.progress("validating vspeed (0x%02x)" % value)
13998
vspeed_ms = value * 0.01 # cm/s -> m/s
13999
vfr_hud = self.assert_receive_message('VFR_HUD')
14000
vfr_hud_vspeed_ms = round(vfr_hud.climb)
14001
self.progress("VFR_HUD climb==%f frsky==%f" % (vfr_hud_vspeed_ms, vspeed_ms))
14002
if self.compare_number_percent(vfr_hud_vspeed_ms, vspeed_ms, 10):
14003
return True
14004
return False
14005
14006
def tfs_validate_battery1(self, value):
14007
self.progress("validating battery1 (0x%02x)" % value)
14008
voltage_v = value * 0.01 # cV -> V
14009
batt = self.assert_receive_message(
14010
'BATTERY_STATUS',
14011
timeout=5,
14012
condition="BATTERY_STATUS.id==0"
14013
)
14014
battery_status_voltage_v = batt.voltages[0] * 0.001 # mV -> V
14015
self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_voltage_v, voltage_v))
14016
if self.compare_number_percent(battery_status_voltage_v, voltage_v, 10):
14017
return True
14018
return False
14019
14020
def tfs_validate_current1(self, value):
14021
# test frsky current vs BATTERY_STATUS
14022
self.progress("validating battery1 (0x%02x)" % value)
14023
current_a = value * 0.1 # dA -> A
14024
batt = self.assert_receive_message(
14025
'BATTERY_STATUS',
14026
timeout=5,
14027
condition="BATTERY_STATUS.id==0"
14028
)
14029
battery_status_current_a = batt.current_battery * 0.01 # cA -> A
14030
self.progress("BATTERY_STATUS current==%f frsky==%f" % (battery_status_current_a, current_a))
14031
if self.compare_number_percent(round(battery_status_current_a * 10), round(current_a * 10), 10):
14032
return True
14033
return False
14034
14035
def tfs_validate_fuel(self, value):
14036
self.progress("validating fuel (0x%02x)" % value)
14037
fuel = value
14038
batt = self.assert_receive_message(
14039
'BATTERY_STATUS',
14040
timeout=5,
14041
condition="BATTERY_STATUS.id==0"
14042
)
14043
battery_status_fuel = batt.battery_remaining
14044
self.progress("BATTERY_STATUS fuel==%f frsky==%f" % (battery_status_fuel, fuel))
14045
if self.compare_number_percent(battery_status_fuel, fuel, 10):
14046
return True
14047
return False
14048
14049
def tfs_validate_tmp1(self, value):
14050
self.progress("validating tmp1 (0x%02x)" % value)
14051
tmp1 = value
14052
heartbeat = self.wait_heartbeat()
14053
heartbeat_tmp1 = heartbeat.custom_mode
14054
self.progress("GLOBAL_POSITION_INT custom_mode==%f frsky==%f" % (heartbeat_tmp1, tmp1))
14055
if heartbeat_tmp1 == tmp1:
14056
return True
14057
return False
14058
14059
def tfs_validate_tmp2(self, value):
14060
self.progress("validating tmp2 (0x%02x)" % value)
14061
tmp2 = value
14062
gps_raw = self.assert_receive_message('GPS_RAW_INT')
14063
gps_raw_tmp2 = gps_raw.satellites_visible*10 + gps_raw.fix_type
14064
self.progress("GPS_RAW_INT tmp2==%f frsky==%f" % (gps_raw_tmp2, tmp2))
14065
if gps_raw_tmp2 == tmp2:
14066
return True
14067
return False
14068
14069
def tfs_validate_rpm(self, value):
14070
self.progress("validating rpm (0x%02x)" % value)
14071
tfs_rpm = value
14072
rpm = self.assert_receive_message('RPM', timeout=5)
14073
rpm_value = round(rpm.rpm1)
14074
self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tfs_rpm))
14075
if rpm_value == tfs_rpm:
14076
return True
14077
return False
14078
14079
def wait_rpm1(self, min_rpm=None, timeout=10):
14080
'''wait for mavlink RPM message to indicate valid RPM'''
14081
tstart = self.get_sim_time()
14082
while True:
14083
t = self.get_sim_time_cached()
14084
if t - tstart > timeout:
14085
raise AutoTestTimeoutException("Failed to do get valid RPM")
14086
rpm = self.mav.recv_match(
14087
type='RPM',
14088
blocking=True,
14089
timeout=1
14090
)
14091
self.progress("rpm: (%s)" % str(rpm))
14092
if rpm is None:
14093
continue
14094
if min_rpm is None:
14095
return
14096
if rpm.rpm1 >= min_rpm:
14097
return
14098
14099
def FRSkySPort(self):
14100
'''Test FrSky SPort mode'''
14101
self.set_parameters({
14102
"SERIAL5_PROTOCOL": 4, # serial5 is FRSky sport
14103
"RPM1_TYPE": 10, # enable SITL RPM sensor
14104
"GPS1_TYPE": 100, # use simulated backend for consistent position
14105
})
14106
port = self.spare_network_port()
14107
self.customise_SITL_commandline([
14108
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14109
])
14110
frsky = FRSkySPort(("127.0.0.1", port), verbose=True)
14111
self.wait_ready_to_arm()
14112
14113
# we need to start the engine to get some RPM readings, we do it for plane only
14114
if self.is_plane():
14115
self.set_autodisarm_delay(0)
14116
if not self.arm_vehicle():
14117
raise NotAchievedException("Failed to ARM")
14118
self.set_rc(3, 1050)
14119
self.wait_rpm1(timeout=10, min_rpm=200)
14120
14121
self.assert_current_onboard_log_contains_message("RPM")
14122
14123
self.drain_mav()
14124
# anything with a lambda in here needs a proper test written.
14125
# This, at least makes sure we're getting some of each
14126
# message.
14127
wants = {
14128
0x082F: self.tfs_validate_gps_alt, # gps altitude integer cm
14129
0x040F: self.tfs_validate_tmp1, # Tmp1
14130
0x060F: self.tfs_validate_fuel, # fuel % 0-100
14131
0x041F: self.tfs_validate_tmp2, # Tmp2
14132
0x010F: self.tfs_validate_baro_alt, # baro alt cm
14133
0x083F: self.tfs_validate_gps_speed, # gps speed integer mm/s
14134
0x084F: self.tfs_validate_yaw, # yaw in cd
14135
0x020F: self.tfs_validate_current1, # current dA
14136
0x011F: self.tfs_validate_vspeed, # vertical speed cm/s
14137
0x021F: self.tfs_validate_battery1, # battery 1 voltage cV
14138
0x0800: self.tf_validate_gps, # gps lat/lon
14139
0x050E: self.tfs_validate_rpm, # rpm 1
14140
}
14141
tstart = self.get_sim_time_cached()
14142
last_wanting_print = 0
14143
14144
last_data_time = None
14145
while len(wants):
14146
now = self.get_sim_time()
14147
if now - last_wanting_print > 1:
14148
self.progress("Still wanting (%s)" %
14149
",".join([("0x%02x" % x) for x in wants.keys()]))
14150
last_wanting_print = now
14151
wants_copy = copy.copy(wants)
14152
if now - tstart > 300:
14153
self.progress("Failed to get frsky passthrough data")
14154
self.progress("Counts of sensor_id polls sent:")
14155
frsky.dump_sensor_id_poll_counts_as_progress_messages()
14156
self.progress("Counts of dataids received:")
14157
frsky.dump_dataid_counts_as_progress_messages()
14158
raise AutoTestTimeoutException("Failed to get frsky sport data")
14159
frsky.update()
14160
if frsky.last_data_time == last_data_time:
14161
continue
14162
last_data_time = frsky.last_data_time
14163
for want in wants_copy:
14164
data = frsky.get_data(want)
14165
if data is None:
14166
continue
14167
self.progress("Checking 0x%x" % (want,))
14168
if wants[want](data):
14169
self.progress(" Fulfilled")
14170
del wants[want]
14171
# ok done, stop the engine
14172
if self.is_plane():
14173
self.zero_throttle()
14174
self.disarm_vehicle(force=True)
14175
14176
def FRSkyD(self):
14177
'''Test FrSkyD serial output'''
14178
self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output
14179
port = self.spare_network_port()
14180
self.customise_SITL_commandline([
14181
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14182
])
14183
frsky = FRSkyD(("127.0.0.1", port))
14184
self.wait_ready_to_arm()
14185
m = self.assert_receive_message('GLOBAL_POSITION_INT')
14186
gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m
14187
14188
# grab a battery-remaining percentage
14189
self.run_cmd(
14190
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
14191
p1=65535, # battery mask
14192
p2=96, # percentage
14193
)
14194
m = self.assert_receive_message('BATTERY_STATUS')
14195
want_battery_remaining_pct = m.battery_remaining
14196
14197
tstart = self.get_sim_time_cached()
14198
have_alt = False
14199
have_battery = False
14200
while True:
14201
t2 = self.get_sim_time_cached()
14202
if t2 - tstart > 10:
14203
raise AutoTestTimeoutException("Failed to get frsky D data")
14204
frsky.update()
14205
14206
alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)
14207
self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))
14208
if alt is None:
14209
continue
14210
if alt == gpi_abs_alt:
14211
have_alt = True
14212
14213
batt = frsky.get_data(frsky.dataid_FUEL)
14214
self.progress("Got batt (%s) mav=%s" % (str(batt), str(want_battery_remaining_pct)))
14215
if batt is None:
14216
continue
14217
if batt == want_battery_remaining_pct:
14218
have_battery = True
14219
14220
if have_alt and have_battery:
14221
break
14222
self.drain_mav()
14223
14224
def test_ltm_g(self, ltm):
14225
g = ltm.g()
14226
if g is None:
14227
return
14228
m = self.assert_receive_message('GLOBAL_POSITION_INT')
14229
print("m: %s" % str(m))
14230
14231
print("g.lat=%s m.lat=%s" % (str(g.lat()), str(m.lat)))
14232
if abs(m.lat - g.lat()) > 10:
14233
return False
14234
14235
print("g.lon:%s m.lon:%s" % (str(g.lon()), str(m.lon)))
14236
if abs(m.lon - g.lon()) > 10:
14237
return False
14238
14239
print("gndspeed: %s" % str(g.gndspeed()))
14240
if g.gndspeed() != 0:
14241
# FIXME if we start the vehicle moving.... check against VFR_HUD?
14242
return False
14243
14244
print("g.alt=%s m.alt=%s" % (str(g.alt()/100.0), str(m.relative_alt/1000.0)))
14245
if abs(m.relative_alt/1000.0 - g.alt()/100.0) > 1:
14246
return False
14247
14248
print("sats: %s" % str(g.sats()))
14249
m = self.assert_receive_message('GPS_RAW_INT')
14250
if m.satellites_visible != g.sats():
14251
return False
14252
14253
constrained_fix_type = m.fix_type
14254
if constrained_fix_type > 3:
14255
constrained_fix_type = 3
14256
print("fix_type: %s" % g.fix_type())
14257
if constrained_fix_type != g.fix_type():
14258
return False
14259
14260
return True
14261
14262
def test_ltm_a(self, ltm):
14263
a = ltm.a()
14264
if a is None:
14265
return
14266
m = self.assert_receive_message('ATTITUDE')
14267
14268
pitch = a.pitch()
14269
print("pitch: %s" % str(pitch))
14270
if abs(math.degrees(m.pitch) - pitch) > 1:
14271
return False
14272
14273
roll = a.roll()
14274
print("roll: %s" % str(roll))
14275
if abs(math.degrees(m.roll) - roll) > 1:
14276
return False
14277
14278
hdg = a.hdg()
14279
myaw = math.degrees(m.yaw)
14280
myaw += 360
14281
myaw %= 360
14282
print("a.hdg=%s m.hdg=%s" % (str(hdg), str(myaw)))
14283
if abs(myaw - hdg) > 1:
14284
return False
14285
14286
return True
14287
14288
def test_ltm_s(self, ltm):
14289
s = ltm.s()
14290
if s is None:
14291
return
14292
# FIXME. Actually check the field values are correct :-)
14293
return True
14294
14295
def LTM(self):
14296
'''Test LTM serial output'''
14297
self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output
14298
port = self.spare_network_port()
14299
self.customise_SITL_commandline([
14300
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14301
])
14302
ltm = LTM(("127.0.0.1", port))
14303
self.wait_ready_to_arm()
14304
14305
wants = {
14306
"g": self.test_ltm_g,
14307
"a": self.test_ltm_a,
14308
"s": self.test_ltm_s,
14309
}
14310
14311
tstart = self.get_sim_time()
14312
while True:
14313
self.progress("Still wanting (%s)" %
14314
",".join([("%s" % x) for x in wants.keys()]))
14315
if len(wants) == 0:
14316
break
14317
now = self.get_sim_time_cached()
14318
if now - tstart > 10:
14319
raise AutoTestTimeoutException("Failed to get ltm data")
14320
14321
ltm.update()
14322
14323
wants_copy = copy.copy(wants)
14324
for want in wants_copy:
14325
self.progress("Checking %s" % (want,))
14326
if wants[want](ltm):
14327
self.progress(" Fulfilled")
14328
del wants[want]
14329
14330
def convertDmsToDdFormat(self, dms):
14331
deg = math.trunc(dms * 1e-7)
14332
dd = deg + (((dms * 1.0e-7) - deg) * 100.0 / 60.0)
14333
if dd < -180.0 or dd > 180.0:
14334
dd = 0.0
14335
return math.trunc(dd * 1.0e7)
14336
14337
def DEVO(self):
14338
'''Test DEVO serial output'''
14339
self.context_push()
14340
self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output
14341
port = self.spare_network_port()
14342
self.customise_SITL_commandline([
14343
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14344
])
14345
devo = DEVO(("127.0.0.1", port))
14346
self.wait_ready_to_arm()
14347
m = self.assert_receive_message('GLOBAL_POSITION_INT')
14348
14349
tstart = self.get_sim_time_cached()
14350
while True:
14351
self.drain_mav()
14352
now = self.get_sim_time_cached()
14353
if now - tstart > 10:
14354
if devo.frame is not None:
14355
# we received some frames but could not find correct values
14356
raise AutoTestTimeoutException("Failed to get correct data")
14357
else:
14358
# No frames received. Devo telemetry is compiled out?
14359
break
14360
14361
devo.update()
14362
frame = devo.frame
14363
if frame is None:
14364
continue
14365
14366
m = self.assert_receive_message('GLOBAL_POSITION_INT')
14367
14368
loc = LocationInt(self.convertDmsToDdFormat(frame.lat()), self.convertDmsToDdFormat(frame.lon()), 0, 0)
14369
14370
print("received lat:%s expected lat:%s" % (str(loc.lat), str(m.lat)))
14371
print("received lon:%s expected lon:%s" % (str(loc.lon), str(m.lon)))
14372
dist_diff = self.get_distance_int(loc, m)
14373
print("Distance:%s" % str(dist_diff))
14374
if abs(dist_diff) > 2:
14375
continue
14376
14377
gpi_rel_alt = int(m.relative_alt / 10) # mm -> cm, since driver send alt in cm
14378
print("received alt:%s expected alt:%s" % (str(frame.alt()), str(gpi_rel_alt)))
14379
if abs(gpi_rel_alt - frame.alt()) > 10:
14380
continue
14381
14382
print("received gndspeed: %s" % str(frame.speed()))
14383
if frame.speed() != 0:
14384
# FIXME if we start the vehicle moving.... check against VFR_HUD?
14385
continue
14386
14387
print("received temp:%s expected temp:%s" % (str(frame.temp()), str(self.mav.messages['HEARTBEAT'].custom_mode)))
14388
if frame.temp() != self.mav.messages['HEARTBEAT'].custom_mode:
14389
# currently we receive mode as temp. This should be fixed when driver is updated
14390
continue
14391
14392
# we match the received voltage with the voltage of primary instance
14393
batt = self.assert_receive_message(
14394
'BATTERY_STATUS',
14395
timeout=5,
14396
condition="BATTERY_STATUS.id==0"
14397
)
14398
volt = batt.voltages[0]*0.001
14399
print("received voltage:%s expected voltage:%s" % (str(frame.volt()*0.1), str(volt)))
14400
if abs(frame.volt()*0.1 - volt) > 0.1:
14401
continue
14402
# if we reach here, exit
14403
break
14404
self.context_pop()
14405
self.reboot_sitl()
14406
14407
def MSP_DJI(self):
14408
'''Test MSP DJI serial output'''
14409
self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output
14410
self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode
14411
port = self.spare_network_port()
14412
self.customise_SITL_commandline([
14413
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14414
])
14415
msp = MSP_DJI(("127.0.0.1", port))
14416
self.wait_ready_to_arm()
14417
14418
tstart = self.get_sim_time()
14419
while True:
14420
self.drain_mav()
14421
if self.get_sim_time_cached() - tstart > 10:
14422
raise NotAchievedException("Did not get location")
14423
msp.update()
14424
try:
14425
f = msp.get_frame(msp.FRAME_GPS_RAW)
14426
except KeyError:
14427
continue
14428
dist = self.get_distance_int(f.LocationInt(), self.sim_location_int())
14429
print("lat=%f lon=%f dist=%f" % (f.lat(), f.lon(), dist))
14430
if dist < 1:
14431
break
14432
14433
def CRSF(self):
14434
'''Test RC CRSF'''
14435
self.context_push()
14436
ex = None
14437
try:
14438
self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input
14439
port = self.spare_network_port()
14440
self.customise_SITL_commandline([
14441
"--serial5=tcp:%u" % port # serial5 reads from to localhost port
14442
])
14443
crsf = CRSF(("127.0.0.1", port))
14444
crsf.connect()
14445
14446
self.progress("Writing vtx_frame")
14447
crsf.write_data_id(crsf.dataid_vtx_frame)
14448
self.delay_sim_time(5)
14449
self.progress("Writing vtx_telem")
14450
crsf.write_data_id(crsf.dataid_vtx_telem)
14451
self.delay_sim_time(5)
14452
self.progress("Writing vtx_unknown")
14453
crsf.write_data_id(crsf.dataid_vtx_unknown)
14454
self.delay_sim_time(5)
14455
except Exception as e:
14456
self.print_exception_caught(e)
14457
ex = e
14458
self.context_pop()
14459
self.disarm_vehicle(force=True)
14460
self.reboot_sitl()
14461
if ex is not None:
14462
raise ex
14463
14464
def CompassPrearms(self):
14465
'''test compass prearm checks'''
14466
self.wait_ready_to_arm()
14467
# XY are checked specially:
14468
for axis in 'X', 'Y': # ArduPilot only checks these two axes
14469
self.context_push()
14470
self.set_parameter(f"COMPASS_OFS2_{axis}", 1000)
14471
self.assert_prearm_failure("Compasses inconsistent")
14472
self.context_pop()
14473
self.wait_ready_to_arm()
14474
14475
# now test the total anglular difference:
14476
self.context_push()
14477
self.set_parameters({
14478
"COMPASS_OFS2_X": 1000,
14479
"COMPASS_OFS2_Y": -1000,
14480
"COMPASS_OFS2_Z": -10000,
14481
})
14482
self.assert_prearm_failure("Compasses inconsistent")
14483
self.context_pop()
14484
self.wait_ready_to_arm()
14485
# the following line papers over a probably problem with the
14486
# EKF recovering from bad compass offsets. Without it, the
14487
# EKF will maintain a 10-degree offset from the true compass
14488
# heading seemingly indefinitely.
14489
self.reboot_sitl()
14490
14491
def run_replay(self, filepath):
14492
'''runs replay in filepath, returns filepath to Replay logfile'''
14493
util.run_cmd(
14494
['build/sitl/tool/Replay', filepath],
14495
directory=util.topdir(),
14496
checkfail=True,
14497
show=True,
14498
output=True,
14499
)
14500
return self.current_onboard_log_filepath()
14501
14502
def AHRS_ORIENTATION(self):
14503
'''test AHRS_ORIENTATION parameter works'''
14504
self.context_push()
14505
self.wait_ready_to_arm()
14506
original_imu = self.assert_receive_message("RAW_IMU", verbose=True)
14507
self.set_parameter("AHRS_ORIENTATION", 16) # roll-90
14508
self.delay_sim_time(2) # we update this on a timer
14509
new_imu = self.assert_receive_message("RAW_IMU", verbose=True)
14510
delta_zacc = original_imu.zacc - new_imu.zacc
14511
delta_z_g = delta_zacc/1000.0 # milligravities -> gravities
14512
if delta_z_g - 1 > 0.1: # milligravities....
14513
raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_z_g=%f)" % (delta_z_g,))
14514
delta_yacc = original_imu.yacc - new_imu.yacc
14515
delta_y_g = delta_yacc/1000.0 # milligravities -> gravities
14516
if delta_y_g + 1 > 0.1:
14517
raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_y_g=%f)" % (delta_y_g,))
14518
self.context_pop()
14519
self.reboot_sitl()
14520
self.delay_sim_time(2) # we update orientation on a timer
14521
14522
def GPSTypes(self):
14523
'''check each simulated GPS works'''
14524
self.reboot_sitl()
14525
orig = self.poll_home_position(timeout=60)
14526
sim_gps = [
14527
# (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix)
14528
# if gps_type is None we auto-detect
14529
# (0, "NONE"),
14530
(1, "UBLOX", None, "u-blox", 5, 'probing'),
14531
(5, "NMEA", 5, "NMEA", 5, 'probing'),
14532
(6, "SBP", None, "SBP", 5, 'probing'),
14533
(8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS
14534
(9, "SBP2", None, "SBP2", 5, 'probing'),
14535
(10, "SBF", 10, 'SBF', 5, 'probing'),
14536
(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS
14537
(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS
14538
# (9, "FILE"),
14539
]
14540
self.context_collect("STATUSTEXT")
14541
for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:
14542
self.start_subtest("Checking GPS type %s" % name)
14543
self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)
14544
self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)
14545
if gps_type is None:
14546
gps_type = 1 # auto-detect
14547
self.set_parameter("GPS1_TYPE", gps_type)
14548
self.context_clear_collection('STATUSTEXT')
14549
self.reboot_sitl()
14550
if detect_prefix == "probing":
14551
self.wait_statustext(f"probing for {detect_name}", check_context=True)
14552
else:
14553
self.wait_statustext(f"specified as {detect_name}", check_context=True)
14554
self.wait_statustext(f"detected {detect_name}", check_context=True)
14555
n = self.poll_home_position(timeout=120)
14556
distance = self.get_distance_int(orig, n)
14557
if distance > 1:
14558
raise NotAchievedException(f"gps type {name} misbehaving")
14559
14560
def assert_gps_satellite_count(self, messagename, count):
14561
m = self.assert_receive_message(messagename)
14562
if m.satellites_visible != count:
14563
raise NotAchievedException("Expected %u sats, got %u" %
14564
(count, m.satellites_visible))
14565
14566
def check_attitudes_match(self):
14567
'''make sure ahrs2 and simstate and ATTTIUDE_QUATERNION all match'''
14568
14569
# these are ordered to bookend the list with timestamps (which
14570
# both attitude messages have):
14571
get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']
14572
msgs = self.get_messages_frame(get_names)
14573
14574
for get_name in get_names:
14575
self.progress("%s: %s" % (get_name, msgs[get_name]))
14576
14577
simstate = msgs['SIMSTATE']
14578
attitude = msgs['ATTITUDE']
14579
ahrs2 = msgs['AHRS2']
14580
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
14581
14582
# check ATTITUDE
14583
want = math.degrees(simstate.roll)
14584
got = math.degrees(attitude.roll)
14585
if abs(mavextra.angle_diff(want, got)) > 20:
14586
raise NotAchievedException("ATTITUDE.Roll looks bad (want=%f got=%f)" %
14587
(want, got))
14588
want = math.degrees(simstate.pitch)
14589
got = math.degrees(attitude.pitch)
14590
if abs(mavextra.angle_diff(want, got)) > 20:
14591
raise NotAchievedException("ATTITUDE.Pitch looks bad (want=%f got=%f)" %
14592
(want, got))
14593
14594
# check AHRS2
14595
want = math.degrees(simstate.roll)
14596
got = math.degrees(ahrs2.roll)
14597
if abs(mavextra.angle_diff(want, got)) > 20:
14598
raise NotAchievedException("AHRS2.Roll looks bad (want=%f got=%f)" %
14599
(want, got))
14600
14601
want = math.degrees(simstate.pitch)
14602
got = math.degrees(ahrs2.pitch)
14603
if abs(mavextra.angle_diff(want, got)) > 20:
14604
raise NotAchievedException("AHRS2.Pitch looks bad (want=%f got=%f)" %
14605
(want, got))
14606
14607
# check ATTITUDE_QUATERNION
14608
q = quaternion.Quaternion([
14609
attitude_quaternion.q1,
14610
attitude_quaternion.q2,
14611
attitude_quaternion.q3,
14612
attitude_quaternion.q4
14613
])
14614
euler = q.euler
14615
self.progress("attquat:%s q:%s euler:%s" % (
14616
str(attitude_quaternion), q, euler))
14617
14618
want = math.degrees(simstate.roll)
14619
got = math.degrees(euler[0])
14620
if mavextra.angle_diff(want, got) > 20:
14621
raise NotAchievedException("quat roll differs from attitude roll; want=%f got=%f" %
14622
(want, got))
14623
14624
want = math.degrees(simstate.pitch)
14625
got = math.degrees(euler[1])
14626
if mavextra.angle_diff(want, got) > 20:
14627
raise NotAchievedException("quat pitch differs from attitude pitch; want=%f got=%f" %
14628
(want, got))
14629
14630
def MultipleGPS(self):
14631
'''check ArduPilot behaviour across multiple GPS units'''
14632
self.assert_message_rate_hz('GPS2_RAW', 0)
14633
14634
# we start sending GPS2_TYPE - but it will never actually be
14635
# filled in as _port[1] is only filled in in AP_GPS::init()
14636
self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")
14637
self.set_parameter("GPS2_TYPE", 1)
14638
self.assert_message_rate_hz('GPS2_RAW', 5)
14639
14640
self.start_subtest("Ensure correct fix type when no connected GPS")
14641
m = self.assert_receive_message("GPS2_RAW")
14642
self.progress(self.dump_message_verbose(m))
14643
if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_NO_GPS:
14644
raise NotAchievedException("Incorrect fix type")
14645
14646
self.start_subtest("Ensure detection when sim gps connected")
14647
self.set_parameter("SIM_GPS2_TYPE", 1)
14648
self.set_parameter("SIM_GPS2_ENABLE", 1)
14649
# a reboot is required after setting GPS2_TYPE. We start
14650
# sending GPS2_RAW out, once the parameter is set, but a
14651
# reboot is required because _port[1] is only set in
14652
# AP_GPS::init() at boot time, so it will never be detected.
14653
self.context_collect("STATUSTEXT")
14654
self.reboot_sitl()
14655
self.wait_statustext("GPS 1: detected u-blox", check_context=True)
14656
self.wait_statustext("GPS 2: detected u-blox", check_context=True)
14657
m = self.assert_receive_message("GPS2_RAW")
14658
self.progress(self.dump_message_verbose(m))
14659
# would be nice for it to take some time to get a fix....
14660
if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_RTK_FIXED:
14661
raise NotAchievedException("Incorrect fix type")
14662
14663
self.start_subtest("Check parameters are per-GPS")
14664
self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)
14665
self.assert_gps_satellite_count("GPS_RAW_INT", 10)
14666
self.set_parameter("SIM_GPS1_NUMSATS", 13)
14667
self.assert_gps_satellite_count("GPS_RAW_INT", 13)
14668
14669
self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)
14670
self.assert_gps_satellite_count("GPS2_RAW", 10)
14671
self.set_parameter("SIM_GPS2_NUMSATS", 12)
14672
self.assert_gps_satellite_count("GPS2_RAW", 12)
14673
14674
self.start_subtest("check that GLOBAL_POSITION_INT fails over")
14675
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14676
gpi_alt = m.alt
14677
for msg in ["GPS_RAW_INT", "GPS2_RAW"]:
14678
m = self.assert_receive_message(msg)
14679
if abs(m.alt - gpi_alt) > 100: # these are in mm
14680
raise NotAchievedException("Alt (%s) discrepancy; %d vs %d" %
14681
(msg, m.alt, gpi_alt))
14682
introduced_error = 10 # in metres
14683
self.set_parameter("SIM_GPS2_ALT_OFS", introduced_error)
14684
self.do_timesync_roundtrip()
14685
m = self.assert_receive_message("GPS2_RAW")
14686
if abs((m.alt-introduced_error*1000) - gpi_alt) > 100:
14687
raise NotAchievedException("skewed Alt (%s) discrepancy; %d+%d vs %d" %
14688
(msg, introduced_error*1000, m.alt, gpi_alt))
14689
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14690
new_gpi_alt = m.alt
14691
if abs(gpi_alt - new_gpi_alt) > 100:
14692
raise NotAchievedException("alt moved unexpectedly")
14693
self.progress("Killing first GPS")
14694
self.set_parameter("SIM_GPS1_ENABLE", 0)
14695
self.delay_sim_time(1)
14696
self.progress("Checking altitude now matches second GPS")
14697
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14698
new_gpi_alt2 = m.alt
14699
m = self.assert_receive_message("GPS2_RAW")
14700
if abs(new_gpi_alt2 - m.alt) > 100:
14701
raise NotAchievedException("Failover not detected")
14702
14703
def fetch_file_via_ftp(self, path, timeout=20):
14704
'''returns the content of the FTP'able file at path'''
14705
self.progress("Retrieving (%s) using MAVProxy" % path)
14706
mavproxy = self.start_mavproxy()
14707
mavproxy.expect("Saved .* parameters to")
14708
ex = None
14709
tmpfile = tempfile.NamedTemporaryFile(mode='r', delete=False)
14710
try:
14711
mavproxy.send("module load ftp\n")
14712
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
14713
mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message
14714
mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))
14715
mavproxy.expect("Getting")
14716
tstart = self.get_sim_time()
14717
while True:
14718
now = self.get_sim_time()
14719
if now - tstart > timeout:
14720
raise NotAchievedException("expected complete transfer")
14721
self.progress("Polling status")
14722
mavproxy.send("ftp status\n")
14723
try:
14724
mavproxy.expect("No transfer in progress", timeout=1)
14725
break
14726
except Exception:
14727
continue
14728
# terminate the connection, or it may still be in progress the next time an FTP is attempted:
14729
mavproxy.send("ftp cancel\n")
14730
mavproxy.expect("Terminated session")
14731
except Exception as e:
14732
self.print_exception_caught(e)
14733
ex = e
14734
14735
self.stop_mavproxy(mavproxy)
14736
14737
if ex is not None:
14738
raise ex
14739
14740
return tmpfile.read()
14741
14742
def MAVFTP(self):
14743
'''ensure MAVProxy can do MAVFTP to ardupilot'''
14744
mavproxy = self.start_mavproxy()
14745
ex = None
14746
try:
14747
mavproxy.send("module load ftp\n")
14748
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
14749
mavproxy.send("ftp list\n")
14750
some_directory = None
14751
for entry in sorted(os.listdir(".")):
14752
if os.path.isdir(entry):
14753
some_directory = entry
14754
break
14755
if some_directory is None:
14756
raise NotAchievedException("No directories?!")
14757
expected_line = " D %s" % some_directory
14758
mavproxy.expect(expected_line) # one line from the ftp list output
14759
except Exception as e:
14760
self.print_exception_caught(e)
14761
ex = e
14762
14763
self.stop_mavproxy(mavproxy)
14764
14765
if ex is not None:
14766
raise ex
14767
14768
def write_content_to_filepath(self, content, filepath):
14769
'''write biunary content to filepath'''
14770
if not isinstance(content, bytes):
14771
raise NotAchievedException("Want bytes to write_content_to_filepath")
14772
with open(filepath, "wb") as f:
14773
f.write(content)
14774
f.close()
14775
14776
def add_embedded_params_to_binary(self, binary, defaults):
14777
sys.path.insert(1, os.path.join(self.rootdir(), 'Tools', 'scripts'))
14778
import apj_tool
14779
14780
# copy binary
14781
if getattr(self, "embedded_default_counter", None) is None:
14782
self.embedded_default_counter = 0
14783
self.embedded_default_counter += 1
14784
14785
new_filepath = binary + "-newdefaults-%u" % self.embedded_default_counter
14786
shutil.copy(binary, new_filepath)
14787
14788
# create file for defaults
14789
defaults_filepath = "embed-these-defaults.txt"
14790
self.write_content_to_filepath(defaults.encode('utf-8'), defaults_filepath)
14791
14792
# do the needful
14793
a = apj_tool.embedded_defaults(new_filepath)
14794
if not a.find():
14795
raise NotAchievedException("Did not find defaults")
14796
a.set_file(defaults_filepath)
14797
a.save()
14798
14799
return new_filepath
14800
14801
def sample_param_file_content(self):
14802
'''returns an array of tuples, (param file content, dictionary of what
14803
parameter values should be tested afterwards)'''
14804
dashes = "-" * 150
14805
return [
14806
# multiple lines:
14807
("""SERIAL5_BAUD 1234
14808
SERIAL4_BAUD=4567
14809
""", {"SERIAL5_BAUD": 1234, "SERIAL4_BAUD": 4567}),
14810
14811
# line missing CR:
14812
("""SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 6789}),
14813
14814
# commented-out line:
14815
("""# SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 57}),
14816
14817
# very long comment line followed by more text:
14818
("""SERIAL4_BAUD 6789
14819
# awesome dashes: %s
14820
SERIAL5_BAUD 128
14821
""" % dashes, {"SERIAL4_BAUD": 6789, "SERIAL5_BAUD": 128}),
14822
14823
]
14824
14825
def EmbeddedParamParser(self):
14826
'''check parsing of embedded defaults file'''
14827
# warning: don't try this test on Copter as it won't boot
14828
# without the passed-in file (which we don't parse if there
14829
# are embedded defaults)
14830
for (content, param_values) in self.sample_param_file_content():
14831
binary_with_defaults = self.add_embedded_params_to_binary(self.binary, content)
14832
self.customise_SITL_commandline([], binary=binary_with_defaults)
14833
self.assert_parameter_values(param_values)
14834
14835
def _MotorTest(self,
14836
command,
14837
timeout=60,
14838
mot1_servo_chan=1,
14839
mot4_servo_chan=4,
14840
wait_finish_text=True,
14841
quadplane=False):
14842
'''Run Motor Tests (with specific mavlink message)'''
14843
self.start_subtest("Testing PWM output")
14844
pwm_in = 1300
14845
# default frame is "+" - start motor of 2 is "B", which is
14846
# motor 1... see
14847
# https://ardupilot.org/copter/docs/connect-escs-and-motors.html
14848
command(
14849
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
14850
p1=2, # start motor
14851
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
14852
p3=pwm_in, # pwm-to-output
14853
p4=2, # timeout in seconds
14854
p5=2, # number of motors to output
14855
p6=0, # compass learning
14856
timeout=timeout,
14857
)
14858
# long timeouts here because there's a pause before we start motors
14859
self.wait_servo_channel_value(mot1_servo_chan, pwm_in, timeout=10)
14860
self.wait_servo_channel_value(mot4_servo_chan, pwm_in, timeout=10)
14861
if wait_finish_text:
14862
self.wait_statustext("finished motor test")
14863
self.wait_disarmed()
14864
# wait_disarmed is not sufficient here; it's actually the
14865
# *motors* being armed which causes the problem, not the
14866
# vehicle's arm state! Could we use SYS_STATUS here instead?
14867
self.delay_sim_time(10)
14868
self.end_subtest("Testing PWM output")
14869
14870
self.start_subtest("Testing percentage output")
14871
percentage = 90.1
14872
# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3
14873
# min/max are used.
14874
expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0
14875
# quadplane doesn't use the expect value - it wants 1900
14876
# rather than the calculated 1901...
14877
if quadplane:
14878
expected_pwm = 1900
14879
self.progress("expected pwm=%f" % expected_pwm)
14880
command(
14881
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
14882
p1=2, # start motor
14883
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,
14884
p3=percentage, # pwm-to-output
14885
p4=2, # timeout in seconds
14886
p5=2, # number of motors to output
14887
p6=0, # compass learning
14888
timeout=timeout,
14889
)
14890
self.wait_servo_channel_value(mot1_servo_chan, expected_pwm, timeout=10)
14891
self.wait_servo_channel_value(mot4_servo_chan, expected_pwm, timeout=10)
14892
if wait_finish_text:
14893
self.wait_statustext("finished motor test")
14894
self.wait_disarmed()
14895
# wait_disarmed is not sufficient here; it's actually the
14896
# *motors* being armed which causes the problem, not the
14897
# vehicle's arm state! Could we use SYS_STATUS here instead?
14898
self.delay_sim_time(10)
14899
self.end_subtest("Testing percentage output")
14900
14901
def MotorTest(self, timeout=60, **kwargs):
14902
'''Run Motor Tests''' # common to Copter and QuadPlane
14903
self._MotorTest(self.run_cmd, **kwargs)
14904
self._MotorTest(self.run_cmd_int, **kwargs)
14905
14906
def test_ibus_voltage(self, message):
14907
batt = self.assert_receive_message(
14908
'BATTERY_STATUS',
14909
timeout=5,
14910
condition="BATTERY_STATUS.id==0"
14911
)
14912
if batt is None:
14913
raise NotAchievedException("Did not get BATTERY_STATUS message")
14914
want = int(batt.voltages[0] * 0.1)
14915
14916
if want != message.get_sensor_value():
14917
raise NotAchievedException("Bad voltage (want=%u got=%u)" %
14918
(want, message.get_sensor_value()))
14919
self.progress("iBus voltage OK")
14920
14921
def test_ibus_armed(self, message):
14922
got = message.get_sensor_value()
14923
want = 1 if self.armed() else 0
14924
if got != want:
14925
raise NotAchievedException("Expected armed %u got %u" %
14926
(want, got))
14927
self.progress("iBus armed OK")
14928
14929
def test_ibus_mode(self, message):
14930
got = message.get_sensor_value()
14931
want = self.mav.messages['HEARTBEAT'].custom_mode
14932
if got != want:
14933
raise NotAchievedException("Expected mode %u got %u" %
14934
(want, got))
14935
self.progress("iBus mode OK")
14936
14937
def test_ibus_get_response(self, ibus, timeout=5):
14938
tstart = self.get_sim_time()
14939
while True:
14940
now = self.get_sim_time()
14941
if now - tstart > timeout:
14942
raise AutoTestTimeoutException("Failed to get ibus data")
14943
packet = ibus.update()
14944
if packet is not None:
14945
return packet
14946
14947
def IBus(self):
14948
'''test the IBus protocol'''
14949
self.set_parameter("SERIAL5_PROTOCOL", 49)
14950
self.customise_SITL_commandline([
14951
"--serial5=tcp:6735" # serial5 spews to localhost:6735
14952
])
14953
ibus = IBus(("127.0.0.1", 6735))
14954
ibus.connect()
14955
14956
# expected_sensors should match the list created in AP_IBus_Telem
14957
expected_sensors = {
14958
# sensor id : (len, IBUS_MEAS_TYPE_*, test_function)
14959
1: (2, 0x15, self.test_ibus_armed),
14960
2: (2, 0x16, self.test_ibus_mode),
14961
5: (2, 0x03, self.test_ibus_voltage),
14962
}
14963
14964
for (sensor_addr, results) in expected_sensors.items():
14965
# first make sure it is present:
14966
request = IBusRequest_DISCOVER(sensor_addr)
14967
ibus.port.sendall(request.for_wire())
14968
14969
packet = self.test_ibus_get_response(ibus)
14970
if packet.address != sensor_addr:
14971
raise ValueError("Unexpected sensor address %u" %
14972
(packet.address,))
14973
14974
(expected_length, expected_type, validator) = results
14975
14976
self.progress("Getting sensor (%x) type" % (sensor_addr))
14977
request = IBusRequest_GET_SENSOR_TYPE(sensor_addr)
14978
ibus.port.sendall(request.for_wire())
14979
14980
packet = self.test_ibus_get_response(ibus)
14981
if packet.address != sensor_addr:
14982
raise ValueError("Unexpected sensor address %u" %
14983
(packet.address,))
14984
14985
if packet.sensor_type != expected_type:
14986
raise ValueError("Unexpected sensor type want=%u got=%u" %
14987
(expected_type, packet.sensor_type))
14988
14989
if packet.sensor_length != expected_length:
14990
raise ValueError("Unexpected sensor len want=%u got=%u" %
14991
(expected_length, packet.sensor_length))
14992
14993
self.progress("Getting sensor (%x) value" % (sensor_addr))
14994
request = IBusRequest_GET_SENSOR_VALUE(sensor_addr)
14995
ibus.port.sendall(request.for_wire())
14996
14997
packet = self.test_ibus_get_response(ibus)
14998
validator(packet)
14999
15000
# self.progress("Ensure we cover all sensors")
15001
# for i in range(1, 17): # zero is special
15002
# if i in expected_sensors:
15003
# continue
15004
# request = IBusRequest_DISCOVER(i)
15005
# ibus.port.sendall(request.for_wire())
15006
15007
# try:
15008
# packet = self.test_ibus_get_response(ibus, timeout=1)
15009
# except AutoTestTimeoutException:
15010
# continue
15011
# self.progress("Received packet (%s)" % str(packet))
15012
# raise NotAchievedException("IBus sensor %u is untested" % i)
15013
15014
def tests(self):
15015
return [
15016
self.PIDTuning,
15017
self.ArmFeatures,
15018
self.SetHome,
15019
self.ConfigErrorLoop,
15020
self.CPUFailsafe,
15021
self.Parameters,
15022
self.LoggerDocumentation,
15023
self.Logging,
15024
self.GetCapabilities,
15025
self.InitialMode,
15026
]
15027
15028
def post_tests_announcements(self):
15029
if self._show_test_timings:
15030
if self.waiting_to_arm_count == 0:
15031
avg = None
15032
else:
15033
avg = self.total_waiting_to_arm_time/self.waiting_to_arm_count
15034
self.progress("Spent %f seconds waiting to arm. count=%u avg=%s" %
15035
(self.total_waiting_to_arm_time,
15036
self.waiting_to_arm_count,
15037
str(avg)))
15038
self.show_test_timings()
15039
if self.forced_post_test_sitl_reboots != 0:
15040
print("Had to force-reset SITL %u times" %
15041
(self.forced_post_test_sitl_reboots,))
15042
15043
def autotest(self, tests=None, allow_skips=True, step_name=None):
15044
"""Autotest used by ArduPilot autotest CI."""
15045
if tests is None:
15046
tests = self.tests()
15047
all_tests = []
15048
for test in tests:
15049
if not isinstance(test, Test):
15050
test = Test(test)
15051
all_tests.append(test)
15052
15053
disabled = self.disabled_tests()
15054
if not allow_skips:
15055
disabled = {}
15056
skip_list = []
15057
tests = []
15058
seen_test_name = set()
15059
for test in all_tests:
15060
if test.name in seen_test_name:
15061
raise ValueError("Duplicate test name %s" % test.name)
15062
seen_test_name.add(test.name)
15063
if test.name in disabled:
15064
self.progress("##### %s is skipped: %s" % (test, disabled[test.name]))
15065
skip_list.append((test, disabled[test.name]))
15066
continue
15067
tests.append(test)
15068
15069
results = self.run_tests(tests)
15070
15071
if len(skip_list):
15072
self.progress("Skipped tests:")
15073
for skipped in skip_list:
15074
(test, reason) = skipped
15075
print(" %s (see %s)" % (test.name, reason))
15076
15077
self.fail_list = list(filter(lambda x : not x.passed, results))
15078
if len(self.fail_list):
15079
self.progress("Failing tests:")
15080
for failure in self.fail_list:
15081
print(str(failure))
15082
15083
self.post_tests_announcements()
15084
if self.generate_junit:
15085
if step_name is None:
15086
step_name = "Unknown_step_name"
15087
step_name.replace(".", "_")
15088
self.create_junit_report(step_name, results, skip_list)
15089
15090
return len(self.fail_list) == 0
15091
15092
def wait_circling_point_with_radius(self, loc, want_radius, epsilon=5.0, min_circle_time=5, timeout=120, track_angle=True):
15093
on_radius_start_heading = None
15094
average_radius = 0.0
15095
done_time = False
15096
done_angle = False
15097
tstart = self.get_sim_time()
15098
circle_time_start = tstart
15099
while True:
15100
now = self.get_sim_time()
15101
if now - tstart > timeout:
15102
raise AutoTestTimeoutException("Did not get onto circle")
15103
here = self.mav.location()
15104
got_radius = self.get_distance(loc, here)
15105
average_radius = 0.95*average_radius + 0.05*got_radius
15106
on_radius = abs(got_radius - want_radius) < epsilon
15107
m = self.assert_receive_message('VFR_HUD')
15108
heading = m.heading
15109
on_string = "off"
15110
got_angle = ""
15111
if on_radius_start_heading is not None:
15112
got_angle = "%0.2f" % abs(on_radius_start_heading - heading) # FIXME
15113
on_string = "on"
15114
15115
want_angle = 180 # we don't actually get this (angle-substraction issue. But we get enough...
15116
got_circle_time = self.get_sim_time() - circle_time_start
15117
bits = [
15118
f"wait-circling: got-r={got_radius:.2f} want-r={want_radius}",
15119
f"avg-r={average_radius} {on_string}",
15120
f"t={got_circle_time:0.2f}/{min_circle_time}",
15121
]
15122
if track_angle:
15123
bits.append(f"want-a={want_angle:0.1f} got-a={got_angle}")
15124
15125
self.progress(" ".join(bits))
15126
if on_radius:
15127
if on_radius_start_heading is None:
15128
on_radius_start_heading = heading
15129
average_radius = got_radius
15130
circle_time_start = now
15131
continue
15132
if abs(on_radius_start_heading - heading) > want_angle: # FIXME
15133
done_angle = True
15134
if got_circle_time > min_circle_time:
15135
done_time = True
15136
if not track_angle:
15137
done_angle = True
15138
if done_time and done_angle:
15139
return
15140
continue
15141
on_radius_start_heading = None
15142
circle_time_start = now
15143
15144
def create_junit_report(self, test_name: str, results: List[Result], skip_list: List[Tuple[Test, Dict[str, str]]]) -> None:
15145
"""Generate Junit report from the autotest results"""
15146
from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure
15147
frame = self.vehicleinfo_key()
15148
xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml"
15149
self.progress(f"Writing test result in jUnit format to {xml_filename}\n")
15150
15151
suite = TestSuite(f"Autotest {frame} {test_name}")
15152
suite.timestamp = datetime.now().replace(microsecond=0).isoformat()
15153
for result in results:
15154
case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed)
15155
# f"{result.test.description}"
15156
# case.file ## TODO : add file properties to match test location
15157
if not result.passed:
15158
case.result = [Failure(f"see {result.debug_filename}", f"{result.exception}")]
15159
suite.add_testcase(case)
15160
for skipped in skip_list:
15161
(test, reason) = skipped
15162
case = TestCase(f"{test.name}", f"{test.function}")
15163
case.result = [Skipped(f"Skipped : {reason}")]
15164
15165
suite.add_property("Firmware Version Major", self.fcu_firmware_version[0])
15166
suite.add_property("Firmware Version Minor", self.fcu_firmware_version[1])
15167
suite.add_property("Firmware Version Rev", self.fcu_firmware_version[2])
15168
suite.add_property("Firmware hash", self.fcu_firmware_hash)
15169
suite.add_property("Git hash", self.githash)
15170
mavproxy_version = util.MAVProxy_version()
15171
suite.add_property("Mavproxy Version Major", mavproxy_version[0])
15172
suite.add_property("Mavproxy Version Minor", mavproxy_version[1])
15173
suite.add_property("Mavproxy Version Rev", mavproxy_version[2])
15174
15175
xml = JUnitXml()
15176
xml.add_testsuite(suite)
15177
xml.write(xml_filename, pretty=True)
15178
15179
def mavfft_fttd(self, sensor_type, sensor_instance, since, until):
15180
'''display fft for raw ACC data in current logfile'''
15181
15182
'''object to store data about a single FFT plot'''
15183
class MessageData(object):
15184
def __init__(self, ffth):
15185
self.seqno = -1
15186
self.fftnum = ffth.N
15187
self.sensor_type = ffth.type
15188
self.instance = ffth.instance
15189
self.sample_rate_hz = ffth.smp_rate
15190
self.multiplier = ffth.mul
15191
self.sample_us = ffth.SampleUS
15192
self.data = {}
15193
self.data["X"] = []
15194
self.data["Y"] = []
15195
self.data["Z"] = []
15196
self.holes = False
15197
self.freq = None
15198
15199
def add_fftd(self, fftd):
15200
self.seqno += 1
15201
self.data["X"].extend(fftd.x)
15202
self.data["Y"].extend(fftd.y)
15203
self.data["Z"].extend(fftd.z)
15204
15205
mlog = self.dfreader_for_current_onboard_log()
15206
15207
# see https://holometer.fnal.gov/GH_FFT.pdf for a description of the techniques used here
15208
messages = []
15209
messagedata = None
15210
while True:
15211
m = mlog.recv_match()
15212
if m is None:
15213
break
15214
msg_type = m.get_type()
15215
if msg_type == "ISBH":
15216
if messagedata is not None:
15217
if (messagedata.sensor_type == sensor_type and
15218
messagedata.instance == sensor_instance and
15219
messagedata.sample_us > since and
15220
messagedata.sample_us < until):
15221
messages.append(messagedata)
15222
messagedata = MessageData(m)
15223
continue
15224
15225
if msg_type == "ISBD":
15226
if (messagedata is not None and
15227
messagedata.sensor_type == sensor_type and
15228
messagedata.instance == sensor_instance):
15229
messagedata.add_fftd(m)
15230
15231
fft_len = len(messages[0].data["X"])
15232
sum_fft = {
15233
"X": numpy.zeros(int(fft_len / 2 + 1)),
15234
"Y": numpy.zeros(int(fft_len / 2 + 1)),
15235
"Z": numpy.zeros(int(fft_len / 2 + 1)),
15236
}
15237
sample_rate = 0
15238
counts = 0
15239
window = numpy.hanning(fft_len)
15240
# The returned float array f contains the frequency bin centers in cycles per unit of the
15241
# sample spacing (with zero at the start).
15242
freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz)
15243
15244
# calculate NEBW constant
15245
S2 = numpy.inner(window, window)
15246
15247
for message in messages:
15248
for axis in ["X", "Y", "Z"]:
15249
# normalize data and convert to dps in order to produce more meaningful magnitudes
15250
if message.sensor_type == 1:
15251
d = numpy.array(numpy.degrees(message.data[axis])) / float(message.multiplier)
15252
else:
15253
d = numpy.array(message.data[axis]) / float(message.multiplier)
15254
15255
# apply window to the input
15256
d *= window
15257
# perform RFFT
15258
d_fft = numpy.fft.rfft(d)
15259
# convert to squared complex magnitude
15260
d_fft = numpy.square(abs(d_fft))
15261
# remove DC component
15262
d_fft[0] = 0
15263
d_fft[-1] = 0
15264
# accumulate the sums
15265
sum_fft[axis] += d_fft
15266
15267
sample_rate = message.sample_rate_hz
15268
counts += 1
15269
15270
numpy.seterr(divide='ignore')
15271
psd = {}
15272
for axis in ["X", "Y", "Z"]:
15273
# normalize output to averaged PSD
15274
psd[axis] = 2 * (sum_fft[axis] / counts) / (sample_rate * S2)
15275
psd[axis] = 10 * numpy.log10(psd[axis])
15276
15277
psd["F"] = freqmap
15278
15279
return psd
15280
15281
def model_defaults_filepath(self, model, vehicleinfo_key=None):
15282
if vehicleinfo_key is None:
15283
vehicle = self.vehicleinfo_key()
15284
else:
15285
vehicle = vehicleinfo_key
15286
15287
vinfo = vehicleinfo.VehicleInfo()
15288
defaults_filepath = vinfo.options[vehicle]["frames"][model]["default_params_filename"]
15289
if isinstance(defaults_filepath, str):
15290
defaults_filepath = [defaults_filepath]
15291
defaults_list = []
15292
for d in defaults_filepath:
15293
defaults_list.append(util.reltopdir(os.path.join(testdir, d)))
15294
return defaults_list
15295
15296
def load_default_params_file(self, filename):
15297
'''load a file from Tools/autotest/default_params'''
15298
filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename))
15299
self.repeatedly_apply_parameter_filepath(filepath)
15300
15301
def load_params_file(self, filename):
15302
'''load a file from test-specific directory'''
15303
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
15304
self.repeatedly_apply_parameter_filepath(filepath)
15305
15306
def send_pause_command(self):
15307
'''pause AUTO/GUIDED modes'''
15308
self.run_cmd(
15309
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
15310
p1=0, # 0: pause, 1: continue
15311
)
15312
15313
def send_resume_command(self):
15314
'''resume AUTO/GUIDED modes'''
15315
self.run_cmd(
15316
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
15317
p1=1, # 0: pause, 1: continue
15318
)
15319
15320
def enum_state_name(self, enum_name, state, pretrim=None):
15321
e = mavutil.mavlink.enums[enum_name]
15322
e_value = e[state]
15323
name = e_value.name
15324
if pretrim is not None:
15325
if not pretrim.startswith(pretrim):
15326
raise NotAchievedException("Expected %s to pretrim" % (pretrim))
15327
name = name.replace(pretrim, "")
15328
return name
15329
15330
def vtol_state_name(self, state):
15331
return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_")
15332
15333
def landed_state_name(self, state):
15334
return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_")
15335
15336
def assert_extended_sys_state(self, vtol_state, landed_state):
15337
m = self.assert_receive_message('EXTENDED_SYS_STATE')
15338
if m.vtol_state != vtol_state:
15339
raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" %
15340
(self.vtol_state_name(vtol_state),
15341
self.vtol_state_name(m.vtol_state)))
15342
if m.landed_state != landed_state:
15343
raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" %
15344
(self.landed_state_name(landed_state),
15345
self.landed_state_name(m.landed_state)))
15346
15347
def wait_extended_sys_state(self, vtol_state, landed_state, timeout=10):
15348
tstart = self.get_sim_time()
15349
while True:
15350
if self.get_sim_time() - tstart > timeout:
15351
raise NotAchievedException("Did not achieve vol/landed states")
15352
self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" %
15353
(self.vtol_state_name(vtol_state),
15354
self.landed_state_name(landed_state)))
15355
m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True)
15356
if m.landed_state != landed_state:
15357
self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" %
15358
(self.landed_state_name(landed_state),
15359
self.landed_state_name(m.landed_state)))
15360
continue
15361
if m.vtol_state != vtol_state:
15362
self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" %
15363
(self.vtol_state_name(vtol_state),
15364
self.vtol_state_name(m.vtol_state)))
15365
continue
15366
15367
self.progress("vtol and landed states match")
15368
return
15369
15370
def setGCSfailsafe(self, paramValue):
15371
# Slow down the sim rate if GCS Failsafe is in use
15372
if paramValue == 0:
15373
self.set_parameters({
15374
"FS_GCS_ENABLE": paramValue,
15375
"SIM_SPEEDUP": 10,
15376
})
15377
else:
15378
self.set_parameters({
15379
"SIM_SPEEDUP": 4,
15380
"FS_GCS_ENABLE": paramValue,
15381
})
15382
15383
def setup_servo_mount(self, roll_servo=5, pitch_servo=6, yaw_servo=7):
15384
'''configure a rpy servo mount; caller responsible for required rebooting'''
15385
self.progress("Setting up servo mount")
15386
self.set_parameters({
15387
"MNT1_TYPE": 1,
15388
"MNT1_PITCH_MIN": -45,
15389
"MNT1_PITCH_MAX": 45,
15390
"RC6_OPTION": 213, # MOUNT1_PITCH
15391
"SERVO%u_FUNCTION" % roll_servo: 8, # roll
15392
"SERVO%u_FUNCTION" % pitch_servo: 7, # pitch
15393
"SERVO%u_FUNCTION" % yaw_servo: 6, # yaw
15394
})
15395
15396