CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

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

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/autotest/vehicle_test_suite.py
Views: 1798
1
'''
2
Common base class for each of the autotest suites
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
from __future__ import print_function
8
9
import abc
10
import copy
11
import errno
12
import glob
13
import math
14
import os
15
import re
16
import shutil
17
import signal
18
import sys
19
import time
20
import traceback
21
from datetime import datetime
22
from typing import List
23
from typing import Tuple
24
from typing import Dict
25
import importlib.util
26
27
import pexpect
28
import fnmatch
29
import operator
30
import numpy
31
import socket
32
import struct
33
import random
34
import tempfile
35
import threading
36
import enum
37
from inspect import currentframe, getframeinfo
38
from pathlib import Path
39
40
from MAVProxy.modules.lib import mp_util
41
from MAVProxy.modules.lib import mp_elevation
42
43
from pymavlink import mavparm
44
from pymavlink import mavwp, mavutil, DFReader
45
from pymavlink import mavextra
46
from pymavlink.rotmat import Vector3
47
from pymavlink import quaternion
48
from pymavlink.generator import mavgen
49
50
from pysim import util, vehicleinfo
51
52
try:
53
import queue as Queue
54
except ImportError:
55
import Queue
56
57
58
# Enumeration convenience class for mavlink POSITION_TARGET_TYPEMASK
59
class MAV_POS_TARGET_TYPE_MASK(enum.IntEnum):
60
POS_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
61
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
62
mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE)
63
VEL_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
64
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
65
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE)
66
ACC_IGNORE = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
67
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
68
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE)
69
FORCE_SET = mavutil.mavlink.POSITION_TARGET_TYPEMASK_FORCE_SET
70
YAW_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE
71
YAW_RATE_IGNORE = mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE
72
POS_ONLY = VEL_IGNORE | ACC_IGNORE | YAW_IGNORE | YAW_RATE_IGNORE
73
LAST_BYTE = 0xF000
74
75
76
MAV_FRAMES_TO_TEST = [
77
mavutil.mavlink.MAV_FRAME_GLOBAL,
78
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
79
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
80
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
81
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
82
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT
83
]
84
85
# get location of scripts
86
testdir = os.path.dirname(os.path.realpath(__file__))
87
88
# Check python version for abstract base class
89
if sys.version_info[0] >= 3 and sys.version_info[1] >= 4:
90
ABC = abc.ABC
91
else:
92
ABC = abc.ABCMeta('ABC', (), {})
93
94
if sys.version_info[0] >= 3:
95
import io as StringIO # srsly, we just did that.
96
else:
97
import StringIO
98
99
try:
100
from itertools import izip as zip
101
except ImportError:
102
# probably python2
103
pass
104
105
106
class ErrorException(Exception):
107
"""Base class for other exceptions"""
108
pass
109
110
111
class AutoTestTimeoutException(ErrorException):
112
pass
113
114
115
if sys.version_info[0] < 3:
116
ConnectionResetError = AutoTestTimeoutException
117
118
119
class WaitModeTimeout(AutoTestTimeoutException):
120
"""Thrown when fails to achieve given mode change."""
121
pass
122
123
124
class WaitAltitudeTimout(AutoTestTimeoutException):
125
"""Thrown when fails to achieve given altitude range."""
126
pass
127
128
129
class WaitGroundSpeedTimeout(AutoTestTimeoutException):
130
"""Thrown when fails to achieve given ground speed range."""
131
pass
132
133
134
class WaitRollTimeout(AutoTestTimeoutException):
135
"""Thrown when fails to achieve given roll in degrees."""
136
pass
137
138
139
class WaitPitchTimeout(AutoTestTimeoutException):
140
"""Thrown when fails to achieve given pitch in degrees."""
141
pass
142
143
144
class WaitHeadingTimeout(AutoTestTimeoutException):
145
"""Thrown when fails to achieve given heading."""
146
pass
147
148
149
class WaitDistanceTimeout(AutoTestTimeoutException):
150
"""Thrown when fails to attain distance"""
151
pass
152
153
154
class WaitLocationTimeout(AutoTestTimeoutException):
155
"""Thrown when fails to attain location"""
156
pass
157
158
159
class WaitWaypointTimeout(AutoTestTimeoutException):
160
"""Thrown when fails to attain waypoint ranges"""
161
pass
162
163
164
class SetRCTimeout(AutoTestTimeoutException):
165
"""Thrown when fails to send RC commands"""
166
pass
167
168
169
class MsgRcvTimeoutException(AutoTestTimeoutException):
170
"""Thrown when fails to receive an expected message"""
171
pass
172
173
174
class NotAchievedException(ErrorException):
175
"""Thrown when fails to achieve a goal"""
176
pass
177
178
179
class OldpymavlinkException(ErrorException):
180
"""Thrown when a new feature is required from pymavlink"""
181
pass
182
183
184
class YawSpeedNotAchievedException(NotAchievedException):
185
"""Thrown when fails to achieve given yaw speed."""
186
pass
187
188
189
class SpeedVectorNotAchievedException(NotAchievedException):
190
"""Thrown when fails to achieve given speed vector."""
191
pass
192
193
194
class PreconditionFailedException(ErrorException):
195
"""Thrown when a precondition for a test is not met"""
196
pass
197
198
199
class ArmedAtEndOfTestException(ErrorException):
200
"""Created when test left vehicle armed"""
201
pass
202
203
204
class Context(object):
205
def __init__(self):
206
self.parameters = []
207
self.sitl_commandline_customised = False
208
self.reboot_sitl_was_done = False
209
self.message_hooks = []
210
self.collections = {}
211
self.heartbeat_interval_ms = 1000
212
self.original_heartbeat_interval_ms = None
213
self.installed_scripts = []
214
self.installed_modules = []
215
self.overridden_message_rates = {}
216
217
218
# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python
219
class TeeBoth(object):
220
def __init__(self, name, mode, mavproxy_logfile, suppress_stdout=False):
221
self.suppress_stdout = suppress_stdout
222
self.file = open(name, mode)
223
self.stdout = sys.stdout
224
self.stderr = sys.stderr
225
self.mavproxy_logfile = mavproxy_logfile
226
self.mavproxy_logfile.set_fh(self)
227
sys.stdout = self
228
sys.stderr = self
229
230
def close(self):
231
sys.stdout = self.stdout
232
sys.stderr = self.stderr
233
self.mavproxy_logfile.set_fh(None)
234
self.mavproxy_logfile = None
235
self.file.close()
236
self.file = None
237
238
def write(self, data):
239
if isinstance(data, bytes):
240
data = data.decode('ascii')
241
self.file.write(data)
242
if not self.suppress_stdout:
243
self.stdout.write(data)
244
245
def flush(self):
246
self.file.flush()
247
248
249
class MAVProxyLogFile(object):
250
def __init__(self):
251
self.fh = None
252
253
def close(self):
254
pass
255
256
def set_fh(self, fh):
257
self.fh = fh
258
259
def write(self, data):
260
if self.fh is not None:
261
self.fh.write(data)
262
else:
263
sys.stdout.write(data)
264
265
def flush(self):
266
if self.fh is not None:
267
self.fh.flush()
268
else:
269
sys.stdout.flush()
270
271
272
class Telem(object):
273
def __init__(self, destination_address, progress_function=None, verbose=False):
274
self.destination_address = destination_address
275
self.progress_function = progress_function
276
self.verbose = verbose
277
278
self.buffer = bytes()
279
self.connected = False
280
self.port = None
281
self.progress_log = ""
282
283
def progress(self, message):
284
message = "%s: %s" % (self.progress_tag(), message)
285
if self.progress_function is not None:
286
self.progress_function(message)
287
return
288
if not self.verbose:
289
self.progress_log += message
290
return
291
print(message)
292
293
def connect(self):
294
try:
295
self.connected = False
296
self.progress("Connecting to (%s:%u)" % self.destination_address)
297
if self.port is not None:
298
try:
299
self.port.close() # might be reopening
300
except Exception:
301
pass
302
self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
303
self.port.connect(self.destination_address)
304
self.port.setblocking(False)
305
self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1)
306
self.connected = True
307
self.progress("Connected")
308
except IOError as e:
309
self.progress("Failed to connect: %s" % str(e))
310
time.sleep(0.5)
311
return False
312
return True
313
314
def do_read(self):
315
try:
316
data = self.port.recv(1024)
317
except socket.error as e:
318
if e.errno not in [errno.EAGAIN, errno.EWOULDBLOCK]:
319
self.progress("Exception: %s" % str(e))
320
self.connected = False
321
return bytes()
322
if len(data) == 0:
323
self.progress("EOF")
324
self.connected = False
325
return bytes()
326
# self.progress("Read %u bytes" % len(data))
327
return data
328
329
def do_write(self, some_bytes):
330
try:
331
written = self.port.send(some_bytes)
332
except socket.error as e:
333
if e.errno in [errno.EAGAIN, errno.EWOULDBLOCK]:
334
return 0
335
self.progress("Exception: %s" % str(e))
336
raise
337
if written != len(some_bytes):
338
raise ValueError("Short write")
339
340
def update(self):
341
if not self.connected:
342
if not self.connect():
343
return
344
return self.update_read()
345
346
347
class IBusMessage(object):
348
def checksum_bytes(self, out):
349
checksum = 0xFFFF
350
for b in iter(out):
351
checksum -= b
352
return checksum
353
354
355
class IBusResponse(IBusMessage):
356
def __init__(self, some_bytes):
357
self.len = some_bytes[0]
358
checksum = self.checksum_bytes(some_bytes[:self.len-2])
359
if checksum >> 8 != some_bytes[self.len-1]:
360
raise ValueError("Checksum bad (-1)")
361
if checksum & 0xff != some_bytes[self.len-2]:
362
raise ValueError("Checksum bad (-2)")
363
self.address = some_bytes[1] & 0x0F
364
self.handle_payload_bytes(some_bytes[2:self.len-2])
365
366
367
class IBusResponse_DISCOVER(IBusResponse):
368
def handle_payload_bytes(self, payload_bytes):
369
if len(payload_bytes):
370
raise ValueError("Not expecting payload bytes (%u)" %
371
(len(payload_bytes), ))
372
373
374
class IBusResponse_GET_SENSOR_TYPE(IBusResponse):
375
def handle_payload_bytes(self, payload_bytes):
376
if len(payload_bytes) != 2:
377
raise ValueError("Expected 2 payload bytes")
378
self.sensor_type = payload_bytes[0]
379
self.sensor_length = payload_bytes[1]
380
381
382
class IBusResponse_GET_SENSOR_VALUE(IBusResponse):
383
def handle_payload_bytes(self, payload_bytes):
384
self.sensor_value = payload_bytes
385
386
def get_sensor_value(self):
387
'''returns an integer based off content'''
388
ret = 0
389
for i in range(len(self.sensor_value)):
390
x = self.sensor_value[i]
391
if sys.version_info.major < 3:
392
x = ord(x)
393
ret = ret | (x << (i*8))
394
return ret
395
396
397
class IBusRequest(IBusMessage):
398
def __init__(self, command, address):
399
self.command = command
400
self.address = address
401
402
def payload_bytes(self):
403
'''most requests don't have a payload'''
404
return bytearray()
405
406
def for_wire(self):
407
out = bytearray()
408
payload_bytes = self.payload_bytes()
409
payload_length = len(payload_bytes)
410
length = 1 + 1 + payload_length + 2 # len+cmd|adr+payloadlen+cksum
411
format_string = '<BB' + ('B' * payload_length)
412
out.extend(struct.pack(format_string,
413
length,
414
(self.command << 4) | self.address,
415
*payload_bytes,
416
))
417
checksum = self.checksum_bytes(out)
418
out.extend(struct.pack("<BB", checksum & 0xff, checksum >> 8))
419
return out
420
421
422
class IBusRequest_DISCOVER(IBusRequest):
423
def __init__(self, address):
424
super(IBusRequest_DISCOVER, self).__init__(0x08, address)
425
426
427
class IBusRequest_GET_SENSOR_TYPE(IBusRequest):
428
def __init__(self, address):
429
super(IBusRequest_GET_SENSOR_TYPE, self).__init__(0x09, address)
430
431
432
class IBusRequest_GET_SENSOR_VALUE(IBusRequest):
433
def __init__(self, address):
434
super(IBusRequest_GET_SENSOR_VALUE, self).__init__(0x0A, address)
435
436
437
class IBus(Telem):
438
def __init__(self, destination_address):
439
super(IBus, self).__init__(destination_address)
440
441
def progress_tag(self):
442
return "IBus"
443
444
def packet_from_buffer(self, buffer):
445
t = buffer[1] >> 4
446
if sys.version_info.major < 3:
447
t = ord(t)
448
if t == 0x08:
449
return IBusResponse_DISCOVER(buffer)
450
if t == 0x09:
451
return IBusResponse_GET_SENSOR_TYPE(buffer)
452
if t == 0x0A:
453
return IBusResponse_GET_SENSOR_VALUE(buffer)
454
raise ValueError("Unknown response type (%u)" % t)
455
456
def update_read(self):
457
self.buffer += self.do_read()
458
while len(self.buffer):
459
msglen = self.buffer[0]
460
if sys.version_info.major < 3:
461
msglen = ord(msglen)
462
if len(self.buffer) < msglen:
463
return
464
packet = self.packet_from_buffer(self.buffer[:msglen])
465
self.buffer = self.buffer[msglen:]
466
return packet
467
468
469
class WaitAndMaintain(object):
470
def __init__(self,
471
test_suite,
472
minimum_duration=None,
473
progress_print_interval=1,
474
timeout=30,
475
epsilon=None,
476
comparator=None,
477
):
478
self.test_suite = test_suite
479
self.minimum_duration = minimum_duration
480
self.achieving_duration_start = None
481
self.timeout = timeout
482
self.epsilon = epsilon
483
self.last_progress_print = 0
484
self.progress_print_interval = progress_print_interval
485
self.comparator = comparator
486
487
def run(self):
488
self.announce_test_start()
489
490
tstart = self.test_suite.get_sim_time_cached()
491
while True:
492
now = self.test_suite.get_sim_time_cached()
493
current_value = self.get_current_value()
494
if now - self.last_progress_print > self.progress_print_interval:
495
self.print_progress(now, current_value)
496
self.last_progress_print = now
497
498
# check for timeout
499
if now - tstart > self.timeout:
500
self.print_failure_text(now, current_value)
501
raise self.timeoutexception()
502
503
# handle the case where we are are achieving our value:
504
if self.validate_value(current_value):
505
if self.achieving_duration_start is None:
506
self.achieving_duration_start = now
507
if (self.minimum_duration is None or
508
now - self.achieving_duration_start > self.minimum_duration):
509
self.announce_success()
510
return True
511
continue
512
513
# handle the case where we are not achieving our value:
514
self.achieving_duration_start = None
515
516
def progress(self, text):
517
self.test_suite.progress(text)
518
519
def announce_test_start(self):
520
self.progress(self.announce_start_text())
521
522
def announce_success(self):
523
self.progress(self.success_text())
524
525
def print_progress(self, now, value):
526
text = self.progress_text(value)
527
if self.achieving_duration_start is not None:
528
delta = now - self.achieving_duration_start
529
text += f" (maintain={delta:.1f}/{self.minimum_duration})"
530
self.progress(text)
531
532
def print_failure_text(self, now, value):
533
'''optionally print a more detailed error string'''
534
pass
535
536
def progress_text(self, value):
537
return f"want={self.get_target_value()} got={value}"
538
539
def validate_value(self, value):
540
target_value = self.get_target_value()
541
if self.comparator is not None:
542
return self.comparator(value, target_value)
543
544
if self.epsilon is not None:
545
return (abs(value - target_value) <= self.epsilon)
546
547
return value == target_value
548
549
def timeoutexception(self):
550
return AutoTestTimeoutException("Failed to attain or maintain value")
551
552
def success_text(self):
553
return f"{type(self)} Success"
554
555
556
class WaitAndMaintainLocation(WaitAndMaintain):
557
def __init__(self, test_suite, target, accuracy=5, height_accuracy=1, **kwargs):
558
super(WaitAndMaintainLocation, self).__init__(test_suite, **kwargs)
559
self.target = target
560
self.height_accuracy = height_accuracy
561
self.accuracy = accuracy
562
563
def announce_start_text(self):
564
t = self.target
565
if self.height_accuracy is not None:
566
return ("Waiting for distance to Location (%.4f, %.4f, %.2f) (h_err<%f, v_err<%.2f " %
567
(t.lat, t.lng, t.alt*0.01, self.accuracy, self.height_accuracy))
568
return ("Waiting for distance to Location (%.4f, %.4f) (h_err<%f" %
569
(t.lat, t.lng, self.accuracy))
570
571
def get_target_value(self):
572
return self.loc
573
574
def get_current_value(self):
575
return self.test_suite.mav.location()
576
577
def horizontal_error(self, value):
578
return self.test_suite.get_distance(value, self.target)
579
580
def vertical_error(self, value):
581
return math.fabs(value.alt*0.01 - self.target.alt*0.01)
582
583
def validate_value(self, value):
584
if self.horizontal_error(value) > self.accuracy:
585
return False
586
587
if self.height_accuracy is None:
588
return True
589
590
if self.vertical_error(value) > self.height_accuracy:
591
return False
592
593
return True
594
595
def success_text(self):
596
return "Reached location"
597
598
def timeoutexception(self):
599
return AutoTestTimeoutException("Failed to attain location")
600
601
def progress_text(self, current_value):
602
if self.height_accuracy is not None:
603
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
604
605
return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}")
606
607
608
class WaitAndMaintainEKFFlags(WaitAndMaintain):
609
'''Waits for EKF status flags to include required_flags and have
610
error_bits *not* set.'''
611
def __init__(self, test_suite, required_flags, error_bits, **kwargs):
612
super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs)
613
self.required_flags = required_flags
614
self.error_bits = error_bits
615
self.last_EKF_STATUS_REPORT = None
616
617
def announce_start_text(self):
618
return f"Waiting for EKF value {self.required_flags}"
619
620
def get_current_value(self):
621
self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10)
622
return self.last_EKF_STATUS_REPORT.flags
623
624
def validate_value(self, value):
625
if value & self.error_bits:
626
return False
627
628
if (value & self.required_flags) != self.required_flags:
629
return False
630
631
return True
632
633
def success_text(self):
634
return "EKF Flags OK"
635
636
def timeoutexception(self):
637
self.progress("Last EKF status report:")
638
self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT))
639
640
return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}")
641
642
def progress_text(self, current_value):
643
error_bits = current_value & self.error_bits
644
return (f"Want={self.required_flags} got={current_value} errors={error_bits}")
645
646
def ekf_flags_string(self, bits):
647
ret = []
648
for i in range(0, 16):
649
bit = 1 << i
650
try:
651
if not bits & bit:
652
continue
653
name = mavutil.mavlink.enums["ESTIMATOR_STATUS_FLAGS"][bit].name
654
trimmed_name = name.removeprefix("ESTIMATOR_")
655
ret.append(trimmed_name)
656
except KeyError:
657
ret.append(str(bit))
658
return "|".join(ret)
659
660
def failure_text(self, now, current_value):
661
components = []
662
components.append(("want", self.ekf_flags_string(self.required_flags)))
663
664
missing_bits = self.required_flags & ~current_value
665
if missing_bits:
666
components.append(("missing", self.ekf_flags_string(missing_bits)))
667
668
error_bits = current_value & self.error_bits
669
if error_bits:
670
components.append(("errors", self.ekf_flags_string(error_bits)))
671
672
return " ".join([f"{n}={v}" for (n, v) in components])
673
674
def print_failure_text(self, now, current_value):
675
self.progress(self.failure_text(now, current_value))
676
677
678
class WaitAndMaintainArmed(WaitAndMaintain):
679
def get_current_value(self):
680
return self.test_suite.armed()
681
682
def get_target_value(self):
683
return True
684
685
def announce_start_text(self):
686
return "Ensuring vehicle remains armed"
687
688
689
class WaitAndMaintainServoChannelValue(WaitAndMaintain):
690
def __init__(self, test_suite, channel, value, **kwargs):
691
super(WaitAndMaintainServoChannelValue, self).__init__(test_suite, **kwargs)
692
self.channel = channel
693
self.value = value
694
695
def announce_start_text(self):
696
str_operator = ""
697
if self.comparator == operator.lt:
698
str_operator = "less than "
699
elif self.comparator == operator.gt:
700
str_operator = "more than "
701
702
return f"Waiting for SERVO_OUTPUT_RAW.servo{self.channel}_value value {str_operator}{self.value}"
703
704
def get_target_value(self):
705
return self.value
706
707
def get_current_value(self):
708
m = self.test_suite.assert_receive_message('SERVO_OUTPUT_RAW', timeout=10)
709
channel_field = "servo%u_raw" % self.channel
710
m_value = getattr(m, channel_field, None)
711
if m_value is None:
712
raise ValueError(f"message ({str(m)}) has no field {channel_field}")
713
714
self.last_SERVO_OUTPUT_RAW = m
715
return m_value
716
717
718
class MSP_Generic(Telem):
719
def __init__(self, destination_address):
720
super(MSP_Generic, self).__init__(destination_address)
721
722
self.callback = None
723
724
self.STATE_IDLE = "IDLE"
725
self.STATE_WANT_HEADER_DOLLARS = "WANT_DOLLARS"
726
self.STATE_WANT_HEADER_M = "WANT_M"
727
self.STATE_WANT_HEADER_GT = "WANT_GT"
728
self.STATE_WANT_DATA_SIZE = "WANT_DATA_SIZE"
729
self.STATE_WANT_COMMAND = "WANT_COMMAND"
730
self.STATE_WANT_DATA = "WANT_DATA"
731
self.STATE_WANT_CHECKSUM = "WANT_CHECKSUM"
732
733
self.state = self.STATE_IDLE
734
735
def progress(self, message):
736
print("MSP: %s" % message)
737
738
def set_state(self, state):
739
# self.progress("Moving to state (%s)" % state)
740
self.state = state
741
742
def init_checksum(self, b):
743
self.checksum = 0
744
self.add_to_checksum(b)
745
746
def add_to_checksum(self, b):
747
self.checksum ^= (b & 0xFF)
748
749
def process_command(self, cmd, data):
750
if self.callback is not None:
751
self.callback(cmd, data)
752
else:
753
print("cmd=%s" % str(cmd))
754
755
def update_read(self):
756
for byte in self.do_read():
757
if sys.version_info[0] < 3:
758
c = byte[0]
759
byte = ord(c)
760
else:
761
c = chr(byte)
762
# print("Got (0x%02x) (%s) (%s) state=%s" % (byte, chr(byte), str(type(byte)), self.state))
763
if self.state == self.STATE_IDLE:
764
# reset state
765
self.set_state(self.STATE_WANT_HEADER_DOLLARS)
766
# deliberate fallthrough right here
767
if self.state == self.STATE_WANT_HEADER_DOLLARS:
768
if c == '$':
769
self.set_state(self.STATE_WANT_HEADER_M)
770
continue
771
if self.state == self.STATE_WANT_HEADER_M:
772
if c != 'M':
773
raise Exception("Malformed packet")
774
self.set_state(self.STATE_WANT_HEADER_GT)
775
continue
776
if self.state == self.STATE_WANT_HEADER_GT:
777
if c != '>':
778
raise Exception("Malformed packet")
779
self.set_state(self.STATE_WANT_DATA_SIZE)
780
continue
781
if self.state == self.STATE_WANT_DATA_SIZE:
782
self.data_size = byte
783
self.set_state(self.STATE_WANT_COMMAND)
784
self.data = bytearray()
785
self.checksum = 0
786
self.add_to_checksum(byte)
787
continue
788
if self.state == self.STATE_WANT_COMMAND:
789
self.command = byte
790
self.add_to_checksum(byte)
791
if self.data_size != 0:
792
self.set_state(self.STATE_WANT_DATA)
793
else:
794
self.set_state(self.STATE_WANT_CHECKSUM)
795
continue
796
if self.state == self.STATE_WANT_DATA:
797
self.add_to_checksum(byte)
798
self.data.append(byte)
799
if len(self.data) == self.data_size:
800
self.set_state(self.STATE_WANT_CHECKSUM)
801
continue
802
if self.state == self.STATE_WANT_CHECKSUM:
803
if self.checksum != byte:
804
raise Exception("Checksum fail (want=0x%02x calced=0x%02x" %
805
(byte, self.checksum))
806
self.process_command(self.command, self.data)
807
self.set_state(self.STATE_IDLE)
808
809
810
class MSP_DJI(MSP_Generic):
811
FRAME_GPS_RAW = 106
812
FRAME_ATTITUDE = 108
813
814
def __init__(self, destination_address):
815
super(MSP_DJI, self).__init__(destination_address)
816
self.callback = self.command_callback
817
self.frames = {}
818
819
class Frame(object):
820
def __init__(self, data):
821
self.data = data
822
823
def intn(self, offset, count):
824
ret = 0
825
for i in range(offset, offset+count):
826
ret = ret | (ord(self.data[i]) << ((i-offset)*8))
827
return ret
828
829
def int32(self, offset):
830
t = struct.unpack("<i", self.data[offset:offset+4])
831
return t[0]
832
833
def int16(self, offset):
834
t = struct.unpack("<h", self.data[offset:offset+2])
835
return t[0]
836
837
class FrameATTITUDE(Frame):
838
def roll(self):
839
'''roll in degrees'''
840
return self.int16(0) * 10
841
842
def pitch(self):
843
'''pitch in degrees'''
844
return self.int16(2) * 10
845
846
def yaw(self):
847
'''yaw in degrees'''
848
return self.int16(4)
849
850
class FrameGPS_RAW(Frame):
851
'''see gps_state_s'''
852
def fix_type(self):
853
return self.uint8(0)
854
855
def num_sats(self):
856
return self.uint8(1)
857
858
def lat(self):
859
return self.int32(2) / 1e7
860
861
def lon(self):
862
return self.int32(6) / 1e7
863
864
def LocationInt(self):
865
# other fields are available, I'm just lazy
866
return LocationInt(self.int32(2), self.int32(6), 0, 0)
867
868
def command_callback(self, frametype, data):
869
# print("X: %s %s" % (str(frametype), str(data)))
870
if frametype == MSP_DJI.FRAME_ATTITUDE:
871
frame = MSP_DJI.FrameATTITUDE(data)
872
elif frametype == MSP_DJI.FRAME_GPS_RAW:
873
frame = MSP_DJI.FrameGPS_RAW(data)
874
else:
875
return
876
self.frames[frametype] = frame
877
878
def get_frame(self, frametype):
879
return self.frames[frametype]
880
881
882
class LTM(Telem):
883
def __init__(self, destination_address):
884
super(LTM, self).__init__(destination_address)
885
886
self.HEADER1 = 0x24
887
self.HEADER2 = 0x54
888
889
self.FRAME_G = 0x47
890
self.FRAME_A = 0x41
891
self.FRAME_S = 0x53
892
893
self.frame_lengths = {
894
self.FRAME_G: 18,
895
self.FRAME_A: 10,
896
self.FRAME_S: 11,
897
}
898
self.frame_lengths = {
899
self.FRAME_G: 18,
900
self.FRAME_A: 10,
901
self.FRAME_S: 11,
902
}
903
904
self.data_by_id = {}
905
self.frames = {}
906
907
def g(self):
908
return self.frames.get(self.FRAME_G, None)
909
910
def a(self):
911
return self.frames.get(self.FRAME_A, None)
912
913
def s(self):
914
return self.frames.get(self.FRAME_S, None)
915
916
def progress_tag(self):
917
return "LTM"
918
919
def handle_data(self, dataid, value):
920
self.progress("%u=%u" % (dataid, value))
921
self.data_by_id[dataid] = value
922
923
def consume_frame(self):
924
b2 = self.buffer[2]
925
if sys.version_info.major < 3:
926
b2 = ord(b2)
927
frame_type = b2
928
frame_length = self.frame_lengths[frame_type]
929
# check frame CRC
930
crc = 0
931
count = 0
932
for c in self.buffer[3:frame_length-1]:
933
if sys.version_info.major < 3:
934
c = ord(c)
935
crc ^= c
936
count += 1
937
buffer_crc = self.buffer[frame_length-1]
938
if sys.version_info.major < 3:
939
buffer_crc = ord(buffer_crc)
940
if crc != buffer_crc:
941
raise NotAchievedException("Invalid checksum on frame type %s" % str(chr(frame_type)))
942
# self.progress("Received valid %s frame" % str(chr(frame_type)))
943
944
class Frame(object):
945
def __init__(self, buffer):
946
self.buffer = buffer
947
948
def intn(self, offset, count):
949
ret = 0
950
for i in range(offset, offset+count):
951
ret = ret | (ord(self.buffer[i]) << ((i-offset)*8))
952
return ret
953
954
def int32(self, offset):
955
t = struct.unpack("<i", self.buffer[offset:offset+4])
956
return t[0]
957
# return self.intn(offset, 4)
958
959
def int16(self, offset):
960
t = struct.unpack("<h", self.buffer[offset:offset+2])
961
return t[0]
962
# return self.intn(offset, 2)
963
964
class FrameG(Frame):
965
def __init__(self, buffer):
966
super(FrameG, self,).__init__(buffer)
967
968
def lat(self):
969
return self.int32(3)
970
971
def lon(self):
972
return self.int32(7)
973
974
def gndspeed(self):
975
ret = self.buffer[11]
976
if sys.version_info.major < 3:
977
ret = ord(ret)
978
return ret
979
980
def alt(self):
981
return self.int32(12)
982
983
def sats(self):
984
s = self.buffer[16]
985
if sys.version_info.major < 3:
986
s = ord(s)
987
return (s >> 2)
988
989
def fix_type(self):
990
s = self.buffer[16]
991
if sys.version_info.major < 3:
992
s = ord(s)
993
return s & 0b11
994
995
class FrameA(Frame):
996
def __init__(self, buffer):
997
super(FrameA, self,).__init__(buffer)
998
999
def pitch(self):
1000
return self.int16(3)
1001
1002
def roll(self):
1003
return self.int16(5)
1004
1005
def hdg(self):
1006
return self.int16(7)
1007
1008
class FrameS(Frame):
1009
def __init__(self, buffer):
1010
super(FrameS, self,).__init__(buffer)
1011
1012
if frame_type == self.FRAME_G:
1013
frame = FrameG(self.buffer[0:frame_length-1])
1014
elif frame_type == self.FRAME_A:
1015
frame = FrameA(self.buffer[0:frame_length-1])
1016
elif frame_type == self.FRAME_S:
1017
frame = FrameS(self.buffer[0:frame_length-1])
1018
else:
1019
raise NotAchievedException("Bad frame?!?!?!")
1020
self.buffer = self.buffer[frame_length:]
1021
self.frames[frame_type] = frame
1022
1023
def update_read(self):
1024
self.buffer += self.do_read()
1025
while len(self.buffer):
1026
if len(self.buffer) == 0:
1027
break
1028
b0 = self.buffer[0]
1029
if sys.version_info.major < 3:
1030
b0 = ord(b0)
1031
if b0 != self.HEADER1:
1032
self.bad_chars += 1
1033
self.buffer = self.buffer[1:]
1034
continue
1035
b1 = self.buffer[1]
1036
if sys.version_info.major < 3:
1037
b1 = ord(b1)
1038
if b1 != self.HEADER2:
1039
self.bad_chars += 1
1040
self.buffer = self.buffer[1:]
1041
continue
1042
b2 = self.buffer[2]
1043
if sys.version_info.major < 3:
1044
b2 = ord(b2)
1045
if b2 not in [self.FRAME_G, self.FRAME_A, self.FRAME_S]:
1046
self.bad_chars += 1
1047
self.buffer = self.buffer[1:]
1048
continue
1049
frame_len = self.frame_lengths[b2]
1050
if len(self.buffer) < frame_len:
1051
continue
1052
self.consume_frame()
1053
1054
def get_data(self, dataid):
1055
try:
1056
return self.data_by_id[dataid]
1057
except KeyError:
1058
pass
1059
return None
1060
1061
1062
class CRSF(Telem):
1063
def __init__(self, destination_address):
1064
super(CRSF, self).__init__(destination_address)
1065
1066
self.dataid_vtx_frame = 0
1067
self.dataid_vtx_telem = 1
1068
self.dataid_vtx_unknown = 2
1069
1070
self.data_id_map = {
1071
self.dataid_vtx_frame: bytearray([0xC8, 0x8, 0xF, 0xCE, 0x30, 0x8, 0x16, 0xE9, 0x0, 0x5F]),
1072
self.dataid_vtx_telem: bytearray([0xC8, 0x7, 0x10, 0xCE, 0xE, 0x16, 0x65, 0x0, 0x1B]),
1073
self.dataid_vtx_unknown: bytearray([0xC8, 0x9, 0x8, 0x0, 0x9E, 0x0, 0x0, 0x0, 0x0, 0x0, 0x95]),
1074
}
1075
1076
def write_data_id(self, dataid):
1077
self.do_write(self.data_id_map[dataid])
1078
1079
def progress_tag(self):
1080
return "CRSF"
1081
1082
1083
class DEVO(Telem):
1084
def __init__(self, destination_address):
1085
super(DEVO, self).__init__(destination_address)
1086
1087
self.HEADER = 0xAA
1088
self.frame_length = 20
1089
1090
# frame is 'None' until we receive a frame with VALID header and checksum
1091
self.frame = None
1092
self.bad_chars = 0
1093
1094
def progress_tag(self):
1095
return "DEVO"
1096
1097
def consume_frame(self):
1098
# check frame checksum
1099
checksum = 0
1100
for c in self.buffer[:self.frame_length-1]:
1101
if sys.version_info.major < 3:
1102
c = ord(c)
1103
checksum += c
1104
checksum &= 0xff # since we receive 8 bit checksum
1105
buffer_checksum = self.buffer[self.frame_length-1]
1106
if sys.version_info.major < 3:
1107
buffer_checksum = ord(buffer_checksum)
1108
if checksum != buffer_checksum:
1109
raise NotAchievedException("Invalid checksum")
1110
1111
class FRAME(object):
1112
def __init__(self, buffer):
1113
self.buffer = buffer
1114
1115
def int32(self, offset):
1116
t = struct.unpack("<i", self.buffer[offset:offset+4])
1117
return t[0]
1118
1119
def int16(self, offset):
1120
t = struct.unpack("<h", self.buffer[offset:offset+2])
1121
return t[0]
1122
1123
def lon(self):
1124
return self.int32(1)
1125
1126
def lat(self):
1127
return self.int32(5)
1128
1129
def alt(self):
1130
return self.int32(9)
1131
1132
def speed(self):
1133
return self.int16(13)
1134
1135
def temp(self):
1136
return self.int16(15)
1137
1138
def volt(self):
1139
return self.int16(17)
1140
1141
self.frame = FRAME(self.buffer[0:self.frame_length-1])
1142
self.buffer = self.buffer[self.frame_length:]
1143
1144
def update_read(self):
1145
self.buffer += self.do_read()
1146
while len(self.buffer):
1147
if len(self.buffer) == 0:
1148
break
1149
b0 = self.buffer[0]
1150
if sys.version_info.major < 3:
1151
b0 = ord(b0)
1152
if b0 != self.HEADER:
1153
self.bad_chars += 1
1154
self.buffer = self.buffer[1:]
1155
continue
1156
if len(self.buffer) < self.frame_length:
1157
continue
1158
self.consume_frame()
1159
1160
1161
class FRSky(Telem):
1162
def __init__(self, destination_address, verbose=False):
1163
super(FRSky, self).__init__(destination_address, verbose=verbose)
1164
1165
self.dataid_GPS_ALT_BP = 0x01
1166
self.dataid_TEMP1 = 0x02
1167
self.dataid_FUEL = 0x04
1168
self.dataid_TEMP2 = 0x05
1169
self.dataid_GPS_ALT_AP = 0x09
1170
self.dataid_BARO_ALT_BP = 0x10
1171
self.dataid_GPS_SPEED_BP = 0x11
1172
self.dataid_GPS_LONG_BP = 0x12
1173
self.dataid_GPS_LAT_BP = 0x13
1174
self.dataid_GPS_COURS_BP = 0x14
1175
self.dataid_GPS_SPEED_AP = 0x19
1176
self.dataid_GPS_LONG_AP = 0x1A
1177
self.dataid_GPS_LAT_AP = 0x1B
1178
self.dataid_BARO_ALT_AP = 0x21
1179
self.dataid_GPS_LONG_EW = 0x22
1180
self.dataid_GPS_LAT_NS = 0x23
1181
self.dataid_CURRENT = 0x28
1182
self.dataid_VFAS = 0x39
1183
1184
1185
class FRSkyD(FRSky):
1186
def __init__(self, destination_address):
1187
super(FRSkyD, self).__init__(destination_address)
1188
1189
self.state_WANT_START_STOP_D = 16,
1190
self.state_WANT_ID = 17
1191
self.state_WANT_BYTE1 = 18
1192
self.state_WANT_BYTE2 = 19
1193
1194
self.START_STOP_D = 0x5E
1195
self.BYTESTUFF_D = 0x5D
1196
1197
self.state = self.state_WANT_START_STOP_D
1198
1199
self.data_by_id = {}
1200
self.bad_chars = 0
1201
1202
def progress_tag(self):
1203
return "FRSkyD"
1204
1205
def handle_data(self, dataid, value):
1206
self.progress("%u=%u" % (dataid, value))
1207
self.data_by_id[dataid] = value
1208
1209
def update_read(self):
1210
self.buffer += self.do_read()
1211
consume = None
1212
while len(self.buffer):
1213
if consume is not None:
1214
self.buffer = self.buffer[consume:]
1215
if len(self.buffer) == 0:
1216
break
1217
consume = 1
1218
if sys.version_info.major >= 3:
1219
b = self.buffer[0]
1220
else:
1221
b = ord(self.buffer[0])
1222
if self.state == self.state_WANT_START_STOP_D:
1223
if b != self.START_STOP_D:
1224
# we may come into a stream mid-way, so we can't judge
1225
self.bad_chars += 1
1226
continue
1227
self.state = self.state_WANT_ID
1228
continue
1229
elif self.state == self.state_WANT_ID:
1230
self.dataid = b
1231
self.state = self.state_WANT_BYTE1
1232
continue
1233
elif self.state in [self.state_WANT_BYTE1, self.state_WANT_BYTE2]:
1234
if b == 0x5D:
1235
# byte-stuffed
1236
if len(self.buffer) < 2:
1237
# try again in a little while
1238
consume = 0
1239
return
1240
if ord(self.buffer[1]) == 0x3E:
1241
b = self.START_STOP_D
1242
elif ord(self.buffer[1]) == 0x3D:
1243
b = self.BYTESTUFF_D
1244
else:
1245
raise ValueError("Unknown stuffed byte")
1246
consume = 2
1247
if self.state == self.state_WANT_BYTE1:
1248
self.b1 = b
1249
self.state = self.state_WANT_BYTE2
1250
continue
1251
1252
data = self.b1 | b << 8
1253
self.handle_data(self.dataid, data)
1254
self.state = self.state_WANT_START_STOP_D
1255
1256
def get_data(self, dataid):
1257
try:
1258
return self.data_by_id[dataid]
1259
except KeyError:
1260
pass
1261
return None
1262
1263
1264
class SPortPacket(object):
1265
def __init__(self):
1266
self.START_STOP_SPORT = 0x7E
1267
self.BYTESTUFF_SPORT = 0x7D
1268
1269
1270
class SPortUplinkPacket(SPortPacket):
1271
def __init__(self, appid0, appid1, data0, data1, data2, data3):
1272
super(SPortUplinkPacket, self).__init__()
1273
self.appid0 = appid0
1274
self.appid1 = appid1
1275
self.data0 = data0
1276
self.data1 = data1
1277
self.data2 = data2
1278
self.data3 = data3
1279
self.SENSOR_ID_UPLINK_ID = 0x0D
1280
self.SPORT_UPLINK_FRAME = 0x30
1281
self.uplink_id = self.SENSOR_ID_UPLINK_ID
1282
self.frame = self.SPORT_UPLINK_FRAME
1283
1284
def packed(self):
1285
return struct.pack(
1286
'<BBBBBBBB',
1287
self.uplink_id,
1288
self.frame,
1289
self.appid0 & 0xff,
1290
self.appid1 & 0xff,
1291
self.data0 & 0xff,
1292
self.data1 & 0xff,
1293
self.data2 & 0xff,
1294
self.data3 & 0xff,
1295
)
1296
1297
def update_checksum(self, byte):
1298
self.checksum += byte
1299
self.checksum += self.checksum >> 8
1300
self.checksum &= 0xFF
1301
1302
def checksum(self):
1303
self.checksum = 0
1304
self.update_checksum(self.frame & 0xff)
1305
self.update_checksum(self.appid0 & 0xff)
1306
self.update_checksum(self.appid1 & 0xff)
1307
self.update_checksum(self.data0 & 0xff)
1308
self.update_checksum(self.data1 & 0xff)
1309
self.update_checksum(self.data2 & 0xff)
1310
self.update_checksum(self.data3 & 0xff)
1311
self.checksum = 0xff - ((self.checksum & 0xff) + (self.checksum >> 8))
1312
return self.checksum & 0xff
1313
1314
def for_wire(self):
1315
out = bytearray()
1316
out.extend(self.packed())
1317
out.extend(struct.pack('<B', self.checksum()))
1318
stuffed = bytearray()
1319
stuffed.extend(struct.pack('<B', self.START_STOP_SPORT))
1320
for pbyte in out:
1321
if pbyte in [self.BYTESTUFF_SPORT,
1322
self.START_STOP_SPORT]:
1323
# bytestuff
1324
stuffed.append(self.BYTESTUFF_SPORT)
1325
stuffed.append(pbyte ^ self.SPORT_FRAME_XOR)
1326
else:
1327
stuffed.append(pbyte)
1328
return stuffed
1329
1330
1331
class SPortPollPacket(SPortPacket):
1332
def __init__(self, sensor):
1333
super(SPortPollPacket, self).__init__()
1334
self.sensor = sensor
1335
1336
def for_wire(self):
1337
return struct.pack(
1338
'<BB',
1339
self.START_STOP_SPORT,
1340
self.sensor & 0xff,
1341
)
1342
1343
1344
class MAVliteMessage(object):
1345
def __init__(self, msgid, body):
1346
self.msgid = msgid
1347
self.body = body
1348
self.SENSOR_ID_UPLINK_ID = 0x0D
1349
self.SPORT_UPLINK_FRAME = 0x30
1350
1351
def checksum_bytes(self, some_bytes):
1352
checksum = 0
1353
for b in some_bytes:
1354
checksum += b
1355
checksum += checksum >> 8
1356
checksum &= 0xFF
1357
return checksum
1358
1359
def to_sport_packets(self):
1360
ret = []
1361
all_bytes = bytearray([len(self.body), self.msgid])
1362
all_bytes.extend(self.body)
1363
1364
# insert sequence numbers:
1365
seq = 0
1366
sequenced = bytearray()
1367
while len(all_bytes):
1368
chunk = all_bytes[0:5]
1369
all_bytes = all_bytes[5:]
1370
sequenced.append(seq)
1371
sequenced.extend(chunk)
1372
seq += 1
1373
1374
# we may need another sport packet just for the checksum:
1375
if len(sequenced) % 6 == 0:
1376
sequenced.append(seq)
1377
seq += 1
1378
1379
checksum = self.checksum_bytes(sequenced)
1380
sequenced.append(checksum)
1381
1382
while len(sequenced):
1383
chunk = sequenced[0:6]
1384
sequenced = sequenced[6:]
1385
chunk.extend([0] * (6-len(chunk))) # pad to 6
1386
packet = SPortUplinkPacket(
1387
*chunk
1388
)
1389
ret.append(packet)
1390
return ret
1391
1392
1393
class SPortToMAVlite(object):
1394
def __init__(self):
1395
self.state_WANT_LEN = "want len"
1396
self.state_WANT_MSGID = "want msgid"
1397
self.state_WANT_PAYLOAD = "want payload"
1398
self.state_WANT_CHECKSUM = "want checksum"
1399
self.state_MESSAGE_RECEIVED = "message received"
1400
1401
self.reset()
1402
1403
def progress(self, message):
1404
print("SPortToMAVLite: %s" % message)
1405
1406
def reset(self):
1407
self.want_seq = 0
1408
self.all_bytes = bytearray()
1409
self.payload = bytearray()
1410
self.state = self.state_WANT_LEN
1411
1412
def checksum_bytes(self, some_bytes):
1413
checksum = 0
1414
for b in some_bytes:
1415
checksum += b
1416
checksum += checksum >> 8
1417
checksum &= 0xFF
1418
return checksum
1419
1420
def downlink_handler(self, some_bytes):
1421
'''adds some_bytes into a mavlite message'''
1422
if some_bytes[0] == 0x00:
1423
self.reset()
1424
if some_bytes[0] != self.want_seq:
1425
raise NotAchievedException("Unexpected seqno; want=%u got=%u" %
1426
(self.want_seq, some_bytes[0]))
1427
self.all_bytes.append(some_bytes[0])
1428
self.want_seq += 1
1429
for byte in some_bytes[1:]:
1430
if self.state == self.state_WANT_LEN:
1431
self.payload_len = byte
1432
self.all_bytes.append(byte)
1433
self.state = self.state_WANT_MSGID
1434
continue
1435
if self.state == self.state_WANT_MSGID:
1436
self.msgid = byte
1437
self.all_bytes.append(byte)
1438
if self.payload_len == 0:
1439
self.state = self.state_WANT_CHECKSUM
1440
else:
1441
self.state = self.state_WANT_PAYLOAD
1442
continue
1443
if self.state == self.state_WANT_PAYLOAD:
1444
self.payload.append(byte)
1445
self.all_bytes.append(byte)
1446
if len(self.payload) == self.payload_len:
1447
self.state = self.state_WANT_CHECKSUM
1448
continue
1449
if self.state == self.state_WANT_CHECKSUM:
1450
calculated_checksum = self.checksum_bytes(self.all_bytes)
1451
if calculated_checksum != byte:
1452
raise Exception("Checksum failure (calc=%u) (recv=%u)" % (calculated_checksum, byte))
1453
self.state = self.state_MESSAGE_RECEIVED
1454
break
1455
1456
def get_message(self):
1457
if self.state != self.state_MESSAGE_RECEIVED:
1458
raise Exception("Wrong state")
1459
return MAVliteMessage(self.msgid, self.payload)
1460
1461
1462
class FRSkySPort(FRSky):
1463
def __init__(self, destination_address, verbose=True, get_time=time.time):
1464
super(FRSkySPort, self).__init__(
1465
destination_address,
1466
verbose=verbose
1467
)
1468
1469
self.get_time = get_time
1470
1471
self.state_SEND_POLL = "sendpoll"
1472
self.state_WANT_FRAME_TYPE = "want_frame_type"
1473
self.state_WANT_ID1 = "want_id1"
1474
self.state_WANT_ID2 = "want id2"
1475
self.state_WANT_DATA = "want data"
1476
self.state_WANT_CRC = "want crc"
1477
1478
self.START_STOP_SPORT = 0x7E
1479
self.BYTESTUFF_SPORT = 0x7D
1480
self.SPORT_DATA_FRAME = 0x10
1481
self.SPORT_DOWNLINK_FRAME = 0x32
1482
self.SPORT_FRAME_XOR = 0x20
1483
1484
self.SENSOR_ID_VARIO = 0x00 # Sensor ID 0
1485
self.SENSOR_ID_FAS = 0x22 # Sensor ID 2
1486
self.SENSOR_ID_GPS = 0x83 # Sensor ID 3
1487
self.SENSOR_ID_RPM = 0xE4 # Sensor ID 4
1488
self.SENSOR_ID_SP2UR = 0xC6 # Sensor ID 6
1489
self.SENSOR_ID_27 = 0x1B # Sensor ID 27
1490
1491
# MAVlite support:
1492
self.SENSOR_ID_DOWNLINK1_ID = 0x34
1493
self.SENSOR_ID_DOWNLINK2_ID = 0x67
1494
self.SENSOR_ID_UPLINK_ID = 0x0D
1495
1496
self.state = self.state_WANT_FRAME_TYPE
1497
1498
self.data_by_id = {}
1499
self.dataid_counts = {}
1500
self.bad_chars = 0
1501
1502
self.poll_sent = 0
1503
self.sensor_id_poll_counts = {}
1504
1505
self.id_descriptions = {
1506
0x5000: "status text (dynamic)",
1507
0x5006: "Attitude and range (dynamic)",
1508
0x800: "GPS lat or lon (600 with 1 sensor)",
1509
0x5005: "Vel and Yaw",
1510
0x5001: "AP status",
1511
0x5002: "GPS Status",
1512
0x5004: "Home",
1513
0x5008: "Battery 2 status",
1514
0x5003: "Battery 1 status",
1515
0x5007: "parameters",
1516
0x500A: "rpm",
1517
0x500B: "terrain",
1518
0x500C: "wind",
1519
1520
# SPort non-passthrough:
1521
0x082F: "GALT", # gps altitude integer cm
1522
0x040F: "TMP1", # Tmp1
1523
0x060F: "Fuel", # fuel % 0-100
1524
0x041F: "TMP2", # Tmp2
1525
0x010F: "ALT", # baro alt cm
1526
0x083F: "GSPD", # gps speed integer mm/s
1527
0x084F: "HDG", # yaw in cd
1528
0x020F: "CURR", # current dA
1529
0x011F: "VSPD", # vertical speed cm/s
1530
0x021F: "VFAS", # battery 1 voltage cV
1531
# 0x800: "GPS", ## comments as duplicated dictrionary key
1532
0x050E: "RPM1",
1533
1534
0x34: "DOWNLINK1_ID",
1535
0x67: "DOWNLINK2_ID",
1536
0x0D: "UPLINK_ID",
1537
}
1538
1539
self.sensors_to_poll = [
1540
self.SENSOR_ID_VARIO,
1541
self.SENSOR_ID_FAS,
1542
self.SENSOR_ID_GPS,
1543
self.SENSOR_ID_RPM,
1544
self.SENSOR_ID_SP2UR,
1545
]
1546
self.next_sensor_id_to_poll = 0 # offset into sensors_to_poll
1547
1548
self.data_downlink_handler = None
1549
1550
self.last_poll_sensor = None
1551
self.last_data_time = None
1552
1553
def progress_tag(self):
1554
return "FRSkySPort"
1555
1556
def handle_data_downlink(self, some_bytes):
1557
self.progress("DOWNLINK %s" % (str(some_bytes),))
1558
if self.data_downlink_handler is not None:
1559
self.data_downlink_handler(some_bytes)
1560
self.last_data_time = self.get_time()
1561
1562
def handle_data(self, dataid, value):
1563
if dataid not in self.id_descriptions:
1564
raise KeyError("dataid 0x%02x" % dataid)
1565
self.progress("%s (0x%x)=%u" % (self.id_descriptions[dataid], dataid, value))
1566
self.data_by_id[dataid] = value
1567
if dataid not in self.dataid_counts:
1568
self.dataid_counts[dataid] = 0
1569
self.dataid_counts[dataid] += 1
1570
self.last_data_time = self.get_time()
1571
1572
def dump_dataid_counts_as_progress_messages(self):
1573
for dataid in self.dataid_counts:
1574
self.progress("0x%x: %u (%s)" % (dataid, self.dataid_counts[dataid], self.id_descriptions[dataid]))
1575
1576
def dump_sensor_id_poll_counts_as_progress_messages(self):
1577
for sensor_id in self.sensor_id_poll_counts:
1578
self.progress("(0x%x): %u" % (sensor_id, self.sensor_id_poll_counts[sensor_id]))
1579
1580
def read_bytestuffed_byte(self):
1581
if sys.version_info.major >= 3:
1582
b = self.buffer[0]
1583
else:
1584
b = ord(self.buffer[0])
1585
if b == 0x7D:
1586
# byte-stuffed
1587
if len(self.buffer) < 2:
1588
self.consume = 0
1589
return None
1590
self.consume = 2
1591
if sys.version_info.major >= 3:
1592
b2 = self.buffer[1]
1593
else:
1594
b2 = ord(self.buffer[1])
1595
if b2 == 0x5E:
1596
return self.START_STOP_SPORT
1597
if b2 == 0x5D:
1598
return self.BYTESTUFF_SPORT
1599
raise ValueError("Unknown stuffed byte (0x%02x)" % b2)
1600
return b
1601
1602
def calc_crc(self, byte):
1603
self.crc += byte
1604
self.crc += self.crc >> 8
1605
self.crc &= 0xFF
1606
1607
def next_sensor(self):
1608
ret = self.sensors_to_poll[self.next_sensor_id_to_poll]
1609
self.next_sensor_id_to_poll += 1
1610
if self.next_sensor_id_to_poll >= len(self.sensors_to_poll):
1611
self.next_sensor_id_to_poll = 0
1612
return ret
1613
1614
def check_poll(self):
1615
now = self.get_time()
1616
# self.progress("check poll (%u)" % now)
1617
1618
# sometimes ArduPilot will not respond to a poll - for
1619
# example, if you poll an unhealthy RPM sensor then we will
1620
# *never* get a response back. So we must re-poll (which
1621
# moves onto the next sensor):
1622
if now - self.poll_sent > 5:
1623
if self.last_poll_sensor is None:
1624
self.progress("Re-polling (last poll sensor was None)")
1625
else:
1626
msg = ("Re-polling (last_poll_sensor=0x%02x state=%s)" %
1627
(self.last_poll_sensor, self.state))
1628
self.progress(msg)
1629
if self.state != self.state_WANT_FRAME_TYPE:
1630
raise ValueError("Expected to be wanting a frame type when repolling (state=%s)" % str(self.state))
1631
self.state = self.state_SEND_POLL
1632
1633
if self.state == self.state_SEND_POLL:
1634
sensor_id = self.next_sensor()
1635
self.progress("Sending poll for 0x%02x" % sensor_id)
1636
self.last_poll_sensor = sensor_id
1637
if sensor_id not in self.sensor_id_poll_counts:
1638
self.sensor_id_poll_counts[sensor_id] = 0
1639
self.sensor_id_poll_counts[sensor_id] += 1
1640
packet = SPortPollPacket(sensor_id)
1641
self.send_sport_packet(packet)
1642
self.state = self.state_WANT_FRAME_TYPE
1643
self.poll_sent = now
1644
1645
def send_sport_packets(self, packets):
1646
for packet in packets:
1647
self.send_sport_packet(packet)
1648
1649
def send_sport_packet(self, packet):
1650
stuffed = packet.for_wire()
1651
self.progress("Sending (%s) (%u)" %
1652
(["0x%02x" % x for x in bytearray(stuffed)], len(stuffed)))
1653
self.port.sendall(stuffed)
1654
1655
def send_mavlite_param_request_read(self, parameter_name):
1656
mavlite_msg = MAVliteMessage(
1657
mavutil.mavlink.MAVLINK_MSG_ID_PARAM_REQUEST_READ,
1658
bytearray(parameter_name.encode())
1659
)
1660
1661
packets = mavlite_msg.to_sport_packets()
1662
1663
self.send_sport_packets(packets)
1664
1665
def send_mavlite_param_set(self, parameter_name, value):
1666
out = bytearray(struct.pack("<f", value))
1667
out.extend(parameter_name.encode())
1668
1669
mavlite_msg = MAVliteMessage(
1670
mavutil.mavlink.MAVLINK_MSG_ID_PARAM_SET,
1671
out
1672
)
1673
1674
packets = mavlite_msg.to_sport_packets()
1675
1676
self.send_sport_packets(packets)
1677
1678
def send_mavlite_command_long(
1679
self,
1680
command,
1681
p1=None,
1682
p2=None,
1683
p3=None,
1684
p4=None,
1685
p5=None,
1686
p6=None,
1687
p7=None,
1688
):
1689
params = bytearray()
1690
seen_none = False
1691
for p in p1, p2, p3, p4, p5, p6, p7:
1692
if p is None:
1693
seen_none = True
1694
continue
1695
if seen_none:
1696
raise ValueError("Can't have values after Nones!")
1697
params.extend(bytearray(struct.pack("<f", p)))
1698
1699
out = bytearray(struct.pack("<H", command)) # first two bytes are command-id
1700
options = len(params) // 4 # low-three-bits is parameter count
1701
out.extend(bytearray(struct.pack("<B", options))) # second byte is options
1702
out.extend(params) # then the float values
1703
1704
mavlite_msg = MAVliteMessage(
1705
mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_LONG,
1706
out
1707
)
1708
1709
packets = mavlite_msg.to_sport_packets()
1710
1711
self.send_sport_packets(packets)
1712
1713
def update(self):
1714
if not self.connected:
1715
if not self.connect():
1716
self.progress("Failed to connect")
1717
return
1718
self.do_sport_read()
1719
self.check_poll()
1720
1721
def do_sport_read(self):
1722
self.buffer += self.do_read()
1723
self.consume = None
1724
while len(self.buffer):
1725
if self.consume is not None:
1726
self.buffer = self.buffer[self.consume:]
1727
if len(self.buffer) == 0:
1728
break
1729
self.consume = 1
1730
if sys.version_info.major >= 3:
1731
b = self.buffer[0]
1732
else:
1733
b = ord(self.buffer[0])
1734
# self.progress("Have (%s) bytes state=%s b=0x%02x" % (str(len(self.buffer)), str(self.state), b));
1735
if self.state == self.state_WANT_FRAME_TYPE:
1736
if b in [self.SPORT_DATA_FRAME, self.SPORT_DOWNLINK_FRAME]:
1737
self.frame = b
1738
self.crc = 0
1739
self.calc_crc(b)
1740
self.state = self.state_WANT_ID1
1741
continue
1742
# we may come into a stream mid-way, so we can't judge
1743
self.progress("############# Bad char %x" % b)
1744
raise ValueError("Bad char (0x%02x)" % b)
1745
self.bad_chars += 1
1746
continue
1747
elif self.state == self.state_WANT_ID1:
1748
self.id1 = self.read_bytestuffed_byte()
1749
if self.id1 is None:
1750
break
1751
self.calc_crc(self.id1)
1752
self.state = self.state_WANT_ID2
1753
continue
1754
elif self.state == self.state_WANT_ID2:
1755
self.id2 = self.read_bytestuffed_byte()
1756
if self.id2 is None:
1757
break
1758
self.calc_crc(self.id2)
1759
self.state = self.state_WANT_DATA
1760
self.data_bytes = []
1761
self.data = 0
1762
continue
1763
elif self.state == self.state_WANT_DATA:
1764
data_byte = self.read_bytestuffed_byte()
1765
if data_byte is None:
1766
break
1767
self.calc_crc(data_byte)
1768
self.data = self.data | (data_byte << (8*(len(self.data_bytes))))
1769
self.data_bytes.append(data_byte)
1770
if len(self.data_bytes) == 4:
1771
self.state = self.state_WANT_CRC
1772
continue
1773
elif self.state == self.state_WANT_CRC:
1774
crc = self.read_bytestuffed_byte()
1775
if crc is None:
1776
break
1777
self.crc = 0xFF - self.crc
1778
dataid = (self.id2 << 8) | self.id1
1779
if self.crc != crc:
1780
self.progress("Incorrect frsky checksum (received=%02x calculated=%02x id=0x%x)" % (crc, self.crc, dataid))
1781
# raise ValueError("Incorrect frsky checksum (want=%02x got=%02x id=0x%x)" % (crc, self.crc, dataid))
1782
else:
1783
if self.frame == self.SPORT_DOWNLINK_FRAME:
1784
self.handle_data_downlink([
1785
self.id1,
1786
self.id2,
1787
self.data_bytes[0],
1788
self.data_bytes[1],
1789
self.data_bytes[2],
1790
self.data_bytes[3]]
1791
)
1792
else:
1793
self.handle_data(dataid, self.data)
1794
self.state = self.state_SEND_POLL
1795
elif self.state == self.state_SEND_POLL:
1796
# this is done in check_poll
1797
self.progress("in send_poll state")
1798
pass
1799
else:
1800
raise ValueError("Unknown state (%s)" % self.state)
1801
1802
def get_data(self, dataid):
1803
try:
1804
return self.data_by_id[dataid]
1805
except KeyError:
1806
pass
1807
return None
1808
1809
1810
class FRSkyPassThrough(FRSkySPort):
1811
def __init__(self, destination_address, get_time=time.time):
1812
super(FRSkyPassThrough, self).__init__(destination_address,
1813
get_time=get_time)
1814
1815
self.sensors_to_poll = [self.SENSOR_ID_27]
1816
1817
def progress_tag(self):
1818
return "FRSkyPassthrough"
1819
1820
1821
class LocationInt(object):
1822
def __init__(self, lat, lon, alt, yaw):
1823
self.lat = lat
1824
self.lon = lon
1825
self.alt = alt
1826
self.yaw = yaw
1827
1828
1829
class Test(object):
1830
'''a test definition - information about a test'''
1831
def __init__(self, function, kwargs={}, attempts=1, speedup=None):
1832
self.name = function.__name__
1833
self.description = function.__doc__
1834
if self.description is None:
1835
raise ValueError("%s is missing a docstring" % self.name)
1836
self.function = function
1837
self.kwargs = kwargs
1838
self.attempts = attempts
1839
self.speedup = speedup
1840
1841
1842
class Result(object):
1843
'''a test result - pass, fail, exception, runtime, ....'''
1844
def __init__(self, test):
1845
self.test = test
1846
self.reason = None
1847
self.exception = None
1848
self.debug_filename = None
1849
self.time_elapsed = 0.0
1850
# self.passed = False
1851
1852
def __str__(self):
1853
ret = " %s (%s)" % (self.test.name, self.test.description)
1854
if self.passed:
1855
return f"{ret} OK"
1856
if self.reason is not None:
1857
ret += f" ({self.reason} )"
1858
if self.exception is not None:
1859
ret += f" ({str(self.exception)})"
1860
if self.debug_filename is not None:
1861
ret += f" (see {self.debug_filename})"
1862
if self.time_elapsed is not None:
1863
ret += f" (duration {self.time_elapsed} s)"
1864
return ret
1865
1866
1867
class ValgrindFailedResult(Result):
1868
'''a custom Result to allow passing of Vaglrind failures around'''
1869
def __init__(self):
1870
super(ValgrindFailedResult, self).__init__(None)
1871
self.passed = False
1872
1873
def __str__(self):
1874
return "Valgrind error detected"
1875
1876
1877
class TestSuite(ABC):
1878
"""Base abstract class.
1879
It implements the common function for all vehicle types.
1880
"""
1881
def __init__(self,
1882
binary,
1883
valgrind=False,
1884
callgrind=False,
1885
gdb=False,
1886
gdb_no_tui=False,
1887
speedup=None,
1888
frame=None,
1889
params=None,
1890
gdbserver=False,
1891
lldb=False,
1892
breakpoints=[],
1893
disable_breakpoints=False,
1894
viewerip=None,
1895
use_map=False,
1896
_show_test_timings=False,
1897
logs_dir=None,
1898
force_ahrs_type=None,
1899
replay=False,
1900
sup_binaries=[],
1901
reset_after_every_test=False,
1902
force_32bit=False,
1903
ubsan=False,
1904
ubsan_abort=False,
1905
num_aux_imus=0,
1906
dronecan_tests=False,
1907
generate_junit=False,
1908
enable_fgview=False,
1909
build_opts={}):
1910
1911
self.start_time = time.time()
1912
1913
if binary is None:
1914
raise ValueError("Should always have a binary")
1915
1916
self.binary = binary
1917
self.valgrind = valgrind
1918
self.callgrind = callgrind
1919
self.gdb = gdb
1920
self.gdb_no_tui = gdb_no_tui
1921
self.lldb = lldb
1922
self.frame = frame
1923
self.params = params
1924
self.gdbserver = gdbserver
1925
self.breakpoints = breakpoints
1926
self.disable_breakpoints = disable_breakpoints
1927
self.speedup = speedup
1928
if self.speedup is None:
1929
self.speedup = self.default_speedup()
1930
self.sup_binaries = sup_binaries
1931
self.reset_after_every_test = reset_after_every_test
1932
self.force_32bit = force_32bit
1933
self.ubsan = ubsan
1934
self.ubsan_abort = ubsan_abort
1935
self.build_opts = build_opts
1936
self.num_aux_imus = num_aux_imus
1937
self.generate_junit = generate_junit
1938
if generate_junit:
1939
try:
1940
spec = importlib.util.find_spec("junitparser")
1941
if spec is None:
1942
raise ImportError
1943
except ImportError as e:
1944
raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python3 -m pip install junitparser")
1945
1946
self.mavproxy = None
1947
self._mavproxy = None # for auto-cleanup on failed tests
1948
self.mav = None
1949
self.viewerip = viewerip
1950
self.use_map = use_map
1951
self.contexts = []
1952
self.context_push()
1953
self.buildlog = None
1954
self.copy_tlog = False
1955
self.logfile = None
1956
self.max_set_rc_timeout = 0
1957
self.last_wp_load = 0
1958
self.forced_post_test_sitl_reboots = 0
1959
self.run_tests_called = False
1960
self._show_test_timings = _show_test_timings
1961
self.test_timings = dict()
1962
self.total_waiting_to_arm_time = 0
1963
self.waiting_to_arm_count = 0
1964
self.force_ahrs_type = force_ahrs_type
1965
self.replay = replay
1966
if self.force_ahrs_type is not None:
1967
self.force_ahrs_type = int(self.force_ahrs_type)
1968
self.logs_dir = logs_dir
1969
self.timesync_number = 137
1970
self.last_progress_sent_as_statustext = None
1971
self.last_heartbeat_time_ms = None
1972
self.last_heartbeat_time_wc_s = 0
1973
self.in_drain_mav = False
1974
self.tlog = None
1975
self.enable_fgview = enable_fgview
1976
1977
self.rc_thread = None
1978
self.rc_thread_should_quit = False
1979
self.rc_queue = Queue.Queue()
1980
1981
self.expect_list = []
1982
1983
self.start_mavproxy_count = 0
1984
1985
self.last_sim_time_cached = 0
1986
self.last_sim_time_cached_wallclock = 0
1987
1988
# to autopilot we do not want to go to the internet for tiles,
1989
# usually. Set this to False to gather tiles from internet in
1990
# the cae there are new tiles required, then add them to the
1991
# repo and set this back to false:
1992
self.terrain_in_offline_mode = True
1993
self.elevationmodel = mp_elevation.ElevationModel(
1994
cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"),
1995
offline=self.terrain_in_offline_mode
1996
)
1997
self.terrain_data_messages_sent = 0 # count of messages back
1998
self.dronecan_tests = dronecan_tests
1999
self.statustext_id = 1
2000
self.message_hooks = [] # functions or MessageHook instances
2001
2002
def __del__(self):
2003
if self.rc_thread is not None:
2004
self.progress("Joining RC thread in __del__")
2005
self.rc_thread_should_quit = True
2006
self.rc_thread.join()
2007
self.rc_thread = None
2008
2009
def default_speedup(self):
2010
return 8
2011
2012
def progress(self, text, send_statustext=True):
2013
"""Display autotest progress text."""
2014
delta_time = time.time() - self.start_time
2015
formatted_text = "AT-%06.1f: %s" % (delta_time, text)
2016
print(formatted_text)
2017
if (send_statustext and
2018
self.mav is not None and
2019
self.mav.port is not None and
2020
self.last_progress_sent_as_statustext != text):
2021
self.send_statustext(formatted_text)
2022
self.last_progress_sent_as_statustext = text
2023
2024
# following two functions swiped from autotest.py:
2025
@staticmethod
2026
def buildlogs_dirpath():
2027
return os.getenv("BUILDLOGS", util.reltopdir("../buildlogs"))
2028
2029
def sitl_home(self):
2030
HOME = self.sitl_start_location()
2031
return "%f,%f,%u,%u" % (HOME.lat,
2032
HOME.lng,
2033
HOME.alt,
2034
HOME.heading)
2035
2036
def mavproxy_version(self):
2037
'''return the current version of mavproxy as a tuple e.g. (1,8,8)'''
2038
return util.MAVProxy_version()
2039
2040
def mavproxy_version_gt(self, major, minor, point):
2041
if os.getenv("AUTOTEST_FORCE_MAVPROXY_VERSION", None) is not None:
2042
return True
2043
(got_major, got_minor, got_point) = self.mavproxy_version()
2044
self.progress("Got: %s.%s.%s" % (got_major, got_minor, got_point))
2045
if got_major > major:
2046
return True
2047
elif got_major < major:
2048
return False
2049
if got_minor > minor:
2050
return True
2051
elif got_minor < minor:
2052
return False
2053
return got_point > point
2054
2055
def open_mavproxy_logfile(self):
2056
return MAVProxyLogFile()
2057
2058
def buildlogs_path(self, path):
2059
"""Return a string representing path in the buildlogs directory."""
2060
bits = [self.buildlogs_dirpath()]
2061
if isinstance(path, list):
2062
bits.extend(path)
2063
else:
2064
bits.append(path)
2065
return os.path.join(*bits)
2066
2067
def sitl_streamrate(self):
2068
"""Allow subclasses to override SITL streamrate."""
2069
return 10
2070
2071
def adjust_ardupilot_port(self, port):
2072
'''adjust port in case we do not wish to use the default range (5760 and 5501 etc)'''
2073
return port
2074
2075
def spare_network_port(self, offset=0):
2076
'''returns a network port which should be able to be bound'''
2077
if offset > 2:
2078
raise ValueError("offset too large")
2079
return 8000 + offset
2080
2081
def autotest_connection_string_to_ardupilot(self):
2082
return "tcp:127.0.0.1:%u" % self.adjust_ardupilot_port(5760)
2083
2084
def sitl_rcin_port(self, offset=0):
2085
if offset > 2:
2086
raise ValueError("offset too large")
2087
return 5501 + offset
2088
2089
def mavproxy_options(self):
2090
"""Returns options to be passed to MAVProxy."""
2091
ret = [
2092
'--streamrate=%u' % self.sitl_streamrate(),
2093
'--target-system=%u' % self.sysid_thismav(),
2094
'--target-component=1',
2095
]
2096
if self.viewerip:
2097
ret.append("--out=%s:14550" % self.viewerip)
2098
if self.use_map:
2099
ret.append('--map')
2100
2101
return ret
2102
2103
def vehicleinfo_key(self):
2104
return self.log_name()
2105
2106
def repeatedly_apply_parameter_filepath(self, filepath):
2107
if False:
2108
return self.repeatedly_apply_parameter_filepath_mavproxy(filepath)
2109
parameters = mavparm.MAVParmDict()
2110
# correct_parameters = set()
2111
if not parameters.load(filepath):
2112
raise ValueError("Param load failed")
2113
param_dict = {}
2114
for p in parameters.keys():
2115
param_dict[p] = parameters[p]
2116
self.set_parameters(param_dict)
2117
2118
def repeatedly_apply_parameter_filepath_mavproxy(self, filepath):
2119
'''keep applying a parameter file until no parameters changed'''
2120
for i in range(0, 3):
2121
self.mavproxy.send("param load %s\n" % filepath)
2122
while True:
2123
line = self.mavproxy.readline()
2124
match = re.match(".*Loaded [0-9]+ parameters.*changed ([0-9]+)",
2125
line)
2126
if match is not None:
2127
if int(match.group(1)) == 0:
2128
return
2129
break
2130
raise NotAchievedException()
2131
2132
def apply_defaultfile_parameters(self):
2133
"""Apply parameter file."""
2134
self.progress("Applying default parameters file")
2135
# setup test parameters
2136
if self.params is None:
2137
self.params = self.model_defaults_filepath(self.frame)
2138
for x in self.params:
2139
self.repeatedly_apply_parameter_filepath(x)
2140
2141
def count_lines_in_filepath(self, filepath):
2142
return len([i for i in open(filepath)])
2143
2144
def count_expected_fence_lines_in_filepath(self, filepath):
2145
count = 0
2146
is_qgc = False
2147
for i in open(filepath):
2148
i = re.sub("#.*", "", i) # trim comments
2149
if i.isspace():
2150
# skip empty lines
2151
continue
2152
if re.match("QGC", i):
2153
# skip QGC header line
2154
is_qgc = True
2155
continue
2156
count += 1
2157
if is_qgc:
2158
count += 2 # file doesn't include return point + closing point
2159
return count
2160
2161
def load_fence_using_mavproxy(self, mavproxy, filename):
2162
self.set_parameter("FENCE_TOTAL", 0)
2163
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2164
count = self.count_expected_fence_lines_in_filepath(filepath)
2165
mavproxy.send('fence load %s\n' % filepath)
2166
# self.mavproxy.expect("Loaded %u (geo-)?fence" % count)
2167
tstart = self.get_sim_time_cached()
2168
while True:
2169
t2 = self.get_sim_time_cached()
2170
if t2 - tstart > 10:
2171
raise AutoTestTimeoutException("Failed to do load")
2172
newcount = self.get_parameter("FENCE_TOTAL")
2173
self.progress("fence total: %u want=%u" % (newcount, count))
2174
if count == newcount:
2175
break
2176
self.delay_sim_time(1)
2177
2178
def get_fence_point(self, idx, target_system=1, target_component=1):
2179
self.mav.mav.fence_fetch_point_send(target_system,
2180
target_component,
2181
idx)
2182
m = self.assert_receive_message("FENCE_POINT", timeout=2)
2183
self.progress("m: %s" % str(m))
2184
if m.idx != idx:
2185
raise NotAchievedException("Invalid idx returned (want=%u got=%u)" %
2186
(idx, m.seq))
2187
return m
2188
2189
def fencepoint_protocol_epsilon(self):
2190
return 0.00002
2191
2192
def roundtrip_fencepoint_protocol(self, offset, count, lat, lng, target_system=1, target_component=1):
2193
self.progress("Sending FENCE_POINT offs=%u count=%u" % (offset, count))
2194
self.mav.mav.fence_point_send(target_system,
2195
target_component,
2196
offset,
2197
count,
2198
lat,
2199
lng)
2200
2201
self.progress("Requesting fence point")
2202
m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)
2203
if abs(m.lat - lat) > self.fencepoint_protocol_epsilon():
2204
raise NotAchievedException("Did not get correct lat in fencepoint: got=%f want=%f" % (m.lat, lat))
2205
if abs(m.lng - lng) > self.fencepoint_protocol_epsilon():
2206
raise NotAchievedException("Did not get correct lng in fencepoint: got=%f want=%f" % (m.lng, lng))
2207
self.progress("Roundtrip OK")
2208
2209
def roundtrip_fence_using_fencepoint_protocol(self, loc_list, target_system=1, target_component=1, ordering=None):
2210
count = len(loc_list)
2211
offset = 0
2212
self.set_parameter("FENCE_TOTAL", count)
2213
if ordering is None:
2214
ordering = range(count)
2215
elif len(ordering) != len(loc_list):
2216
raise ValueError("ordering list length mismatch")
2217
2218
for offset in ordering:
2219
loc = loc_list[offset]
2220
self.roundtrip_fencepoint_protocol(offset,
2221
count,
2222
loc.lat,
2223
loc.lng,
2224
target_system,
2225
target_component)
2226
2227
self.progress("Validating uploaded fence")
2228
returned_count = self.get_parameter("FENCE_TOTAL")
2229
if returned_count != count:
2230
raise NotAchievedException("Returned count mismatch (want=%u got=%u)" %
2231
(count, returned_count))
2232
for i in range(count):
2233
self.progress("Requesting fence point")
2234
m = self.get_fence_point(offset, target_system=target_system, target_component=target_component)
2235
if abs(m.lat-loc.lat) > self.fencepoint_protocol_epsilon():
2236
raise NotAchievedException("Returned lat mismatch (want=%f got=%f" %
2237
(loc.lat, m.lat))
2238
if abs(m.lng-loc.lng) > self.fencepoint_protocol_epsilon():
2239
raise NotAchievedException("Returned lng mismatch (want=%f got=%f" %
2240
(loc.lng, m.lng))
2241
if m.count != count:
2242
raise NotAchievedException("Count mismatch (want=%u got=%u)" %
2243
(count, m.count))
2244
2245
def load_fence(self, filename):
2246
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2247
if not os.path.exists(filepath):
2248
filepath = self.generic_mission_filepath_for_filename(filename)
2249
self.progress("Loading fence from (%s)" % str(filepath))
2250
locs = []
2251
for line in open(filepath, 'rb'):
2252
if len(line) == 0:
2253
continue
2254
m = re.match(r"([-\d.]+)\s+([-\d.]+)\s*", line.decode('ascii'))
2255
if m is None:
2256
raise ValueError("Did not match (%s)" % line)
2257
locs.append(mavutil.location(float(m.group(1)), float(m.group(2)), 0, 0))
2258
if self.is_plane():
2259
# create return point as the centroid:
2260
total_lat = 0
2261
total_lng = 0
2262
total_cnt = 0
2263
for loc in locs:
2264
total_lat += loc.lat
2265
total_lng += loc.lng
2266
total_cnt += 1
2267
locs2 = [mavutil.location(total_lat/total_cnt,
2268
total_lng/total_cnt,
2269
0,
2270
0)] # return point
2271
locs2.extend(locs)
2272
locs2.append(copy.copy(locs2[1]))
2273
return self.roundtrip_fence_using_fencepoint_protocol(locs2)
2274
2275
self.upload_fences_from_locations([
2276
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, locs),
2277
])
2278
2279
def load_fence_using_mavwp(self, filename):
2280
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
2281
if not os.path.exists(filepath):
2282
filepath = self.generic_mission_filepath_for_filename(filename)
2283
self.progress("Loading fence from (%s)" % str(filepath))
2284
items = self.mission_item_protocol_items_from_filepath(mavwp.MissionItemProtocol_Fence, filepath)
2285
self.check_fence_upload_download(items)
2286
2287
def send_reboot_command(self):
2288
self.mav.mav.command_long_send(self.sysid_thismav(),
2289
1,
2290
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2291
1, # confirmation
2292
1, # reboot autopilot
2293
0,
2294
0,
2295
0,
2296
0,
2297
0,
2298
0)
2299
2300
def reboot_check_valgrind_log(self):
2301
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
2302
model=self.frame)
2303
if os.path.isfile(valgrind_log) and (os.path.getsize(valgrind_log) > 0):
2304
backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))
2305
shutil.move(valgrind_log, backup_valgrind_log)
2306
2307
def run_cmd_reboot(self):
2308
self.run_cmd_int(
2309
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2310
p1=1, # reboot autopilot
2311
)
2312
2313
def run_cmd_enable_high_latency(self, new_state, run_cmd=None):
2314
if run_cmd is None:
2315
run_cmd = self.run_cmd
2316
p1 = 0
2317
if new_state:
2318
p1 = 1
2319
2320
run_cmd(
2321
mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY,
2322
p1=p1, # enable/disable
2323
)
2324
2325
def reboot_sitl_mav(self, required_bootcount=None, force=False):
2326
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
2327
# we must make sure that stats have been reset - otherwise
2328
# when we reboot we'll reset statistics again and lose our
2329
# STAT_BOOTCNT increment:
2330
tstart = time.time()
2331
while True:
2332
if time.time() - tstart > 30:
2333
raise NotAchievedException("STAT_RESET did not go non-zero")
2334
if self.get_parameter('STAT_RESET', timeout_in_wallclock=True) != 0:
2335
break
2336
2337
old_bootcount = self.get_parameter('STAT_BOOTCNT')
2338
# ardupilot SITL may actually NAK the reboot; replace with
2339
# run_cmd when we don't do that.
2340
do_context = False
2341
if self.valgrind or self.callgrind:
2342
self.reboot_check_valgrind_log()
2343
self.progress("Stopping and restarting SITL")
2344
if getattr(self, 'valgrind_restart_customisations', None) is not None:
2345
self.customise_SITL_commandline(
2346
self.valgrind_restart_customisations,
2347
model=self.valgrind_restart_model,
2348
defaults_filepath=self.valgrind_restart_defaults_filepath,
2349
)
2350
else:
2351
self.stop_SITL()
2352
self.start_SITL(wipe=False)
2353
else:
2354
# receiving an ACK from the process turns out to be really
2355
# quite difficult. So just send it and hope for the best.
2356
self.progress("Sending reboot command")
2357
p6 = 0
2358
if force:
2359
p6 = 20190226 # magic force-reboot value
2360
self.send_cmd(
2361
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2362
p1=1,
2363
p2=1,
2364
p6=p6,
2365
)
2366
do_context = True
2367
if do_context:
2368
self.context_push()
2369
2370
def hook(mav, m):
2371
if m.get_type() != 'COMMAND_ACK':
2372
return
2373
if m.command != mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
2374
return
2375
self.progress("While awaiting reboot received (%s)" % str(m))
2376
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
2377
raise NotAchievedException("Bad reboot ACK detected")
2378
self.install_message_hook_context(hook)
2379
2380
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
2381
2382
if do_context:
2383
self.context_pop()
2384
2385
def send_cmd_enter_cpu_lockup(self):
2386
"""Poke ArduPilot to stop the main loop from running"""
2387
self.mav.mav.command_long_send(self.sysid_thismav(),
2388
1,
2389
mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
2390
1, # confirmation
2391
42, # lockup autopilot
2392
24, # no, really, we mean it
2393
71, # seriously, we're not kidding
2394
93, # we know exactly what we're
2395
0,
2396
0,
2397
0)
2398
2399
def reboot_sitl(self,
2400
required_bootcount=None,
2401
force=False,
2402
check_position=True,
2403
mark_context=True,
2404
startup_location_dist_max=1,
2405
):
2406
"""Reboot SITL instance and wait for it to reconnect."""
2407
if self.armed() and not force:
2408
raise NotAchievedException("Reboot attempted while armed")
2409
self.progress("Rebooting SITL")
2410
self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force)
2411
self.do_heartbeats(force=True)
2412
if check_position and self.frame != 'sailboat': # sailboats drift with wind!
2413
self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max)
2414
if mark_context:
2415
self.context_get().reboot_sitl_was_done = True
2416
2417
def reboot_sitl_mavproxy(self, required_bootcount=None):
2418
"""Reboot SITL instance using MAVProxy and wait for it to reconnect."""
2419
old_bootcount = self.get_parameter('STAT_BOOTCNT')
2420
self.mavproxy.send("reboot\n")
2421
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
2422
2423
def detect_and_handle_reboot(self, old_bootcount, required_bootcount=None, timeout=10):
2424
tstart = time.time()
2425
if required_bootcount is None:
2426
required_bootcount = old_bootcount + 1
2427
while True:
2428
if time.time() - tstart > timeout:
2429
raise AutoTestTimeoutException("Did not detect reboot")
2430
try:
2431
current_bootcount = self.get_parameter('STAT_BOOTCNT',
2432
timeout=1,
2433
attempts=1,
2434
verbose=True,
2435
timeout_in_wallclock=True)
2436
self.progress("current=%s required=%u" %
2437
(str(current_bootcount), required_bootcount))
2438
if current_bootcount == required_bootcount:
2439
break
2440
except NotAchievedException:
2441
pass
2442
except AutoTestTimeoutException:
2443
pass
2444
except ConnectionResetError:
2445
pass
2446
except socket.error:
2447
pass
2448
except Exception as e:
2449
self.progress("Got unexpected exception (%s)" % str(type(e)))
2450
pass
2451
2452
# empty mav to avoid getting old timestamps:
2453
self.do_timesync_roundtrip(timeout_in_wallclock=True)
2454
2455
self.progress("Calling initialise-after-reboot")
2456
self.initialise_after_reboot_sitl()
2457
2458
def scripting_restart(self):
2459
'''restart scripting subsystem'''
2460
self.progress("Restarting Scripting")
2461
self.run_cmd_int(
2462
mavutil.mavlink.MAV_CMD_SCRIPTING,
2463
p1=mavutil.mavlink.SCRIPTING_CMD_STOP_AND_RESTART,
2464
timeout=5,
2465
)
2466
2467
def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):
2468
'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''
2469
self.do_timesync_roundtrip(timeout_in_wallclock=True)
2470
tstart = time.time()
2471
while True:
2472
if time.time() - tstart > timeout:
2473
raise NotAchievedException("Failed to set streamrate")
2474
self.mav.mav.request_data_stream_send(
2475
1,
2476
1,
2477
stream,
2478
streamrate,
2479
1)
2480
m = self.mav.recv_match(type='SYSTEM_TIME',
2481
blocking=True,
2482
timeout=1)
2483
if m is not None:
2484
break
2485
2486
def set_streamrate_mavproxy(self, streamrate, timeout=10):
2487
tstart = time.time()
2488
while True:
2489
if time.time() - tstart > timeout:
2490
raise AutoTestTimeoutException("stream rate change failed")
2491
2492
self.mavproxy.send("set streamrate %u\n" % (streamrate))
2493
self.mavproxy.send("set streamrate\n")
2494
try:
2495
self.mavproxy.expect('.*streamrate ((?:-)?[0-9]+)', timeout=1)
2496
except pexpect.TIMEOUT:
2497
continue
2498
rate = self.mavproxy.match.group(1)
2499
# self.progress("rate: %s" % str(rate))
2500
if int(rate) == int(streamrate):
2501
break
2502
2503
if streamrate <= 0:
2504
return
2505
2506
self.progress("Waiting for SYSTEM_TIME for confirmation streams are working")
2507
self.drain_mav_unparsed()
2508
timeout = 60
2509
tstart = time.time()
2510
while True:
2511
self.drain_all_pexpects()
2512
if time.time() - tstart > timeout:
2513
raise NotAchievedException("Did not get SYSTEM_TIME within %f seconds" % timeout)
2514
m = self.mav.recv_match(timeout=0.1)
2515
if m is None:
2516
continue
2517
# self.progress("Received (%s)" % str(m))
2518
if m.get_type() == 'SYSTEM_TIME':
2519
break
2520
self.drain_mav()
2521
2522
def htree_from_xml(self, xml_filepath):
2523
'''swiped from mavproxy_param.py'''
2524
xml = open(xml_filepath, 'rb').read()
2525
from lxml import objectify
2526
objectify.enable_recursive_str()
2527
tree = objectify.fromstring(xml)
2528
htree = {}
2529
for p in tree.vehicles.parameters.param:
2530
n = p.get('name').split(':')[1]
2531
htree[n] = p
2532
for lib in tree.libraries.parameters:
2533
for p in lib.param:
2534
n = p.get('name')
2535
htree[n] = p
2536
return htree
2537
2538
def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None):
2539
self.progress("Sending ABSD_VEHICLE message")
2540
new = here
2541
if offset_ne is not None:
2542
new = self.offset_location_ne(new, offset_ne[0], offset_ne[1])
2543
self.mav.mav.adsb_vehicle_send(
2544
37, # ICAO address
2545
int(new.lat * 1e7),
2546
int(new.lng * 1e7),
2547
mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH,
2548
int(here.alt*1000 + 10000), # 10m up
2549
0, # heading in cdeg
2550
0, # horizontal velocity cm/s
2551
0, # vertical velocity cm/s
2552
"bob".encode("ascii"), # callsign
2553
mavutil.mavlink.ADSB_EMITTER_TYPE_LIGHT,
2554
1, # time since last communication
2555
65535, # flags
2556
17 # squawk
2557
)
2558
2559
def get_sim_parameter_documentation_get_whitelist(self):
2560
# common parameters
2561
ret = set([
2562
"SIM_ACC_TRIM_X",
2563
"SIM_ACC_TRIM_Y",
2564
"SIM_ACC_TRIM_Z",
2565
"SIM_ARSPD2_OFS",
2566
"SIM_ARSPD2_RND",
2567
"SIM_ARSPD_OFS",
2568
"SIM_ARSPD_RND",
2569
"SIM_FTOWESC_ENA",
2570
"SIM_FTOWESC_POW",
2571
"SIM_IE24_ENABLE",
2572
"SIM_IE24_ERROR",
2573
"SIM_IE24_STATE",
2574
"SIM_IMUT1_ACC1_X",
2575
"SIM_IMUT1_ACC1_Y",
2576
"SIM_IMUT1_ACC1_Z",
2577
"SIM_IMUT1_ACC2_X",
2578
"SIM_IMUT1_ACC2_Y",
2579
"SIM_IMUT1_ACC2_Z",
2580
"SIM_IMUT1_ACC3_X",
2581
"SIM_IMUT1_ACC3_Y",
2582
"SIM_IMUT1_ACC3_Z",
2583
"SIM_IMUT1_ENABLE",
2584
"SIM_IMUT1_GYR1_X",
2585
"SIM_IMUT1_GYR1_Y",
2586
"SIM_IMUT1_GYR1_Z",
2587
"SIM_IMUT1_GYR2_X",
2588
"SIM_IMUT1_GYR2_Y",
2589
"SIM_IMUT1_GYR2_Z",
2590
"SIM_IMUT1_GYR3_X",
2591
"SIM_IMUT1_GYR3_Y",
2592
"SIM_IMUT1_GYR3_Z",
2593
"SIM_IMUT1_TMAX",
2594
"SIM_IMUT1_TMIN",
2595
"SIM_IMUT2_ACC1_X",
2596
"SIM_IMUT2_ACC1_Y",
2597
"SIM_IMUT2_ACC1_Z",
2598
"SIM_IMUT2_ACC2_X",
2599
"SIM_IMUT2_ACC2_Y",
2600
"SIM_IMUT2_ACC2_Z",
2601
"SIM_IMUT2_ACC3_X",
2602
"SIM_IMUT2_ACC3_Y",
2603
"SIM_IMUT2_ACC3_Z",
2604
"SIM_IMUT2_ENABLE",
2605
"SIM_IMUT2_GYR1_X",
2606
"SIM_IMUT2_GYR1_Y",
2607
"SIM_IMUT2_GYR1_Z",
2608
"SIM_IMUT2_GYR2_X",
2609
"SIM_IMUT2_GYR2_Y",
2610
"SIM_IMUT2_GYR2_Z",
2611
"SIM_IMUT2_GYR3_X",
2612
"SIM_IMUT2_GYR3_Y",
2613
"SIM_IMUT2_GYR3_Z",
2614
"SIM_IMUT2_TMAX",
2615
"SIM_IMUT2_TMIN",
2616
"SIM_IMUT3_ACC1_X",
2617
"SIM_IMUT3_ACC1_Y",
2618
"SIM_IMUT3_ACC1_Z",
2619
"SIM_IMUT3_ACC2_X",
2620
"SIM_IMUT3_ACC2_Y",
2621
"SIM_IMUT3_ACC2_Z",
2622
"SIM_IMUT3_ACC3_X",
2623
"SIM_IMUT3_ACC3_Y",
2624
"SIM_IMUT3_ACC3_Z",
2625
"SIM_IMUT3_ENABLE",
2626
"SIM_IMUT3_GYR1_X",
2627
"SIM_IMUT3_GYR1_Y",
2628
"SIM_IMUT3_GYR1_Z",
2629
"SIM_IMUT3_GYR2_X",
2630
"SIM_IMUT3_GYR2_Y",
2631
"SIM_IMUT3_GYR2_Z",
2632
"SIM_IMUT3_GYR3_X",
2633
"SIM_IMUT3_GYR3_Y",
2634
"SIM_IMUT3_GYR3_Z",
2635
"SIM_IMUT3_TMAX",
2636
"SIM_IMUT3_TMIN",
2637
"SIM_IMUT4_ACC1_X",
2638
"SIM_IMUT4_ACC1_Y",
2639
"SIM_IMUT4_ACC1_Z",
2640
"SIM_IMUT4_ACC2_X",
2641
"SIM_IMUT4_ACC2_Y",
2642
"SIM_IMUT4_ACC2_Z",
2643
"SIM_IMUT4_ACC3_X",
2644
"SIM_IMUT4_ACC3_Y",
2645
"SIM_IMUT4_ACC3_Z",
2646
"SIM_IMUT4_ENABLE",
2647
"SIM_IMUT4_GYR1_X",
2648
"SIM_IMUT4_GYR1_Y",
2649
"SIM_IMUT4_GYR1_Z",
2650
"SIM_IMUT4_GYR2_X",
2651
"SIM_IMUT4_GYR2_Y",
2652
"SIM_IMUT4_GYR2_Z",
2653
"SIM_IMUT4_GYR3_X",
2654
"SIM_IMUT4_GYR3_Y",
2655
"SIM_IMUT4_GYR3_Z",
2656
"SIM_IMUT4_TMAX",
2657
"SIM_IMUT4_TMIN",
2658
"SIM_IMUT5_ACC1_X",
2659
"SIM_IMUT5_ACC1_Y",
2660
"SIM_IMUT5_ACC1_Z",
2661
"SIM_IMUT5_ACC2_X",
2662
"SIM_IMUT5_ACC2_Y",
2663
"SIM_IMUT5_ACC2_Z",
2664
"SIM_IMUT5_ACC3_X",
2665
"SIM_IMUT5_ACC3_Y",
2666
"SIM_IMUT5_ACC3_Z",
2667
"SIM_IMUT5_ENABLE",
2668
"SIM_IMUT5_GYR1_X",
2669
"SIM_IMUT5_GYR1_Y",
2670
"SIM_IMUT5_GYR1_Z",
2671
"SIM_IMUT5_GYR2_X",
2672
"SIM_IMUT5_GYR2_Y",
2673
"SIM_IMUT5_GYR2_Z",
2674
"SIM_IMUT5_GYR3_X",
2675
"SIM_IMUT5_GYR3_Y",
2676
"SIM_IMUT5_GYR3_Z",
2677
"SIM_IMUT5_TMAX",
2678
"SIM_IMUT5_TMIN",
2679
"SIM_MAG2_DIA_X",
2680
"SIM_MAG2_DIA_Y",
2681
"SIM_MAG2_DIA_Z",
2682
"SIM_MAG2_ODI_X",
2683
"SIM_MAG2_ODI_Y",
2684
"SIM_MAG2_ODI_Z",
2685
"SIM_MAG2_OFS_X",
2686
"SIM_MAG2_OFS_Y",
2687
"SIM_MAG2_OFS_Z",
2688
"SIM_MAG3_DIA_X",
2689
"SIM_MAG3_DIA_Y",
2690
"SIM_MAG3_DIA_Z",
2691
"SIM_MAG3_ODI_X",
2692
"SIM_MAG3_ODI_Y",
2693
"SIM_MAG3_ODI_Z",
2694
"SIM_MAG3_OFS_X",
2695
"SIM_MAG3_OFS_Y",
2696
"SIM_MAG3_OFS_Z",
2697
"SIM_MAG_ALY_X",
2698
"SIM_MAG_ALY_Y",
2699
"SIM_MAG_ALY_Z",
2700
"SIM_MAG1_DIA_X",
2701
"SIM_MAG1_DIA_Y",
2702
"SIM_MAG1_DIA_Z",
2703
"SIM_MAG_MOT_X",
2704
"SIM_MAG_MOT_Y",
2705
"SIM_MAG_MOT_Z",
2706
"SIM_MAG1_ODI_X",
2707
"SIM_MAG1_ODI_Y",
2708
"SIM_MAG1_ODI_Z",
2709
"SIM_MAG1_OFS_X",
2710
"SIM_MAG1_OFS_Y",
2711
"SIM_MAG1_OFS_Z",
2712
"SIM_PARA_ENABLE",
2713
"SIM_PARA_PIN",
2714
"SIM_RICH_CTRL",
2715
"SIM_RICH_ENABLE",
2716
"SIM_SHIP_DSIZE",
2717
"SIM_SHIP_ENABLE",
2718
"SIM_SHIP_OFS_X",
2719
"SIM_SHIP_OFS_Y",
2720
"SIM_SHIP_OFS_Z",
2721
"SIM_SHIP_PSIZE",
2722
"SIM_SHIP_SPEED",
2723
"SIM_SHIP_SYSID",
2724
"SIM_TA_ENABLE",
2725
"SIM_VIB_FREQ_X",
2726
"SIM_VIB_FREQ_Y",
2727
"SIM_VIB_FREQ_Z",
2728
])
2729
2730
vinfo_key = self.vehicleinfo_key()
2731
if vinfo_key == "Rover":
2732
ret.update([
2733
])
2734
if vinfo_key == "ArduSub":
2735
ret.update([
2736
"SIM_BUOYANCY",
2737
])
2738
2739
return ret
2740
2741
def test_parameter_documentation_get_all_parameters(self):
2742
# this is a set of SIM_parameters which we know aren't currently
2743
# documented - but they really should be. We use this whitelist
2744
# to ensure any new SIM_ parameters added are documented
2745
sim_parameters_missing_documentation = self.get_sim_parameter_documentation_get_whitelist()
2746
2747
xml_filepath = os.path.join(self.buildlogs_dirpath(), "apm.pdef.xml")
2748
param_parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'param_metadata', 'param_parse.py')
2749
try:
2750
os.unlink(xml_filepath)
2751
except OSError:
2752
pass
2753
vehicle = self.log_name()
2754
if vehicle == "HeliCopter":
2755
vehicle = "ArduCopter"
2756
if vehicle == "QuadPlane":
2757
vehicle = "ArduPlane"
2758
cmd = [param_parse_filepath, '--vehicle', vehicle]
2759
# cmd.append("--verbose")
2760
if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:
2761
self.progress("Failed param_parse.py (%s)" % vehicle)
2762
return False
2763
htree = self.htree_from_xml(xml_filepath)
2764
2765
target_system = self.sysid_thismav()
2766
target_component = 1
2767
2768
self.customise_SITL_commandline([
2769
"--unhide-groups"
2770
])
2771
2772
(parameters, seq_id) = self.download_parameters(target_system, target_component)
2773
2774
self.reset_SITL_commandline()
2775
2776
fail = False
2777
for param in parameters.keys():
2778
if param.startswith("SIM_"):
2779
if param in sim_parameters_missing_documentation:
2780
if param in htree:
2781
self.progress("%s is in both XML and whitelist; remove it from the whitelist" % param)
2782
fail = True
2783
# hopefully these get documented sometime....
2784
continue
2785
if param not in htree:
2786
self.progress("%s not in XML" % param)
2787
fail = True
2788
if fail:
2789
raise NotAchievedException("Downloaded parameters missing in XML")
2790
2791
self.progress("There are %u SIM_ parameters left to document" % len(sim_parameters_missing_documentation))
2792
2793
# FIXME: this should be doable if we filter out e.g BRD_* and CAN_*?
2794
# self.progress("Checking no extra parameters present in XML")
2795
# fail = False
2796
# for param in htree:
2797
# if param.startswith("SIM_"):
2798
# # too many of these to worry about
2799
# continue
2800
# if param not in parameters:
2801
# print("%s not in downloaded parameters but in XML" % param)
2802
# fail = True
2803
# if fail:
2804
# raise NotAchievedException("Extra parameters in XML")
2805
2806
def find_format_defines(self, lines):
2807
ret = {}
2808
for line in lines:
2809
if isinstance(line, bytes):
2810
line = line.decode("utf-8")
2811
m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line)
2812
if m is None:
2813
continue
2814
(a, b) = (m.group(1), m.group(2))
2815
if a in ret:
2816
raise NotAchievedException("Duplicate define for (%s)" % a)
2817
ret[a] = b
2818
return ret
2819
2820
def vehicle_code_dirpath(self):
2821
'''returns path to vehicle-specific code directory e.g. ~/ardupilot/Rover'''
2822
dirname = self.log_name()
2823
if dirname == "QuadPlane":
2824
dirname = "ArduPlane"
2825
elif dirname == "HeliCopter":
2826
dirname = "ArduCopter"
2827
return os.path.join(self.rootdir(), dirname)
2828
2829
def find_LogStructureFiles(self):
2830
'''return list of files named LogStructure.h'''
2831
ret = []
2832
for root, _, files in os.walk(self.rootdir()):
2833
for f in files:
2834
if f == 'LogStructure.h':
2835
ret.append(os.path.join(root, f))
2836
if f == 'LogStructure_SBP.h':
2837
ret.append(os.path.join(root, f))
2838
return ret
2839
2840
def all_log_format_ids(self):
2841
'''parse C++ code to extract definitions of log messages'''
2842
structure_files = self.find_LogStructureFiles()
2843
structure_lines = []
2844
for f in structure_files:
2845
structure_lines.extend(open(f).readlines())
2846
2847
defines = self.find_format_defines(structure_lines)
2848
2849
ids = {}
2850
message_infos = []
2851
for f in structure_files:
2852
self.progress("structure file: %s" % f)
2853
state_outside = 0
2854
state_inside = 1
2855
state = state_outside
2856
2857
linestate_none = 45
2858
linestate_within = 46
2859
linestate = linestate_none
2860
debug = False
2861
if f == "/home/pbarker/rc/ardupilot/libraries/AP_HAL_ChibiOS/LogStructure.h":
2862
debug = True
2863
for line in open(f).readlines():
2864
if debug:
2865
print("line: %s" % line)
2866
if isinstance(line, bytes):
2867
line = line.decode("utf-8")
2868
line = re.sub("//.*", "", line) # trim comments
2869
if re.match(r"\s*$", line):
2870
# blank line
2871
continue
2872
if state == state_outside:
2873
if ("#define LOG_COMMON_STRUCTURES" in line or
2874
re.match("#define LOG_STRUCTURE_FROM_.*", line)):
2875
if debug:
2876
self.progress("Moving inside")
2877
state = state_inside
2878
continue
2879
if state == state_inside:
2880
if linestate == linestate_none:
2881
allowed_list = ['LOG_STRUCTURE_FROM_']
2882
2883
allowed = False
2884
for a in allowed_list:
2885
if a in line:
2886
allowed = True
2887
if allowed:
2888
continue
2889
m = re.match(r"\s*{(.*)},\s*", line)
2890
if m is not None:
2891
# complete line
2892
if debug:
2893
print("Complete line: %s" % str(line))
2894
message_infos.append(m.group(1))
2895
continue
2896
m = re.match(r"\s*{(.*)\\", line)
2897
if m is None:
2898
if debug:
2899
self.progress("Moving outside")
2900
state = state_outside
2901
continue
2902
partial_line = m.group(1)
2903
if debug:
2904
self.progress("partial line")
2905
linestate = linestate_within
2906
continue
2907
if linestate == linestate_within:
2908
if debug:
2909
self.progress("Looking for close-brace")
2910
m = re.match("(.*)}", line)
2911
if m is None:
2912
if debug:
2913
self.progress("no close-brace")
2914
line = line.rstrip()
2915
newline = re.sub(r"\\$", "", line)
2916
if newline == line:
2917
raise NotAchievedException("Expected backslash at end of line")
2918
line = newline
2919
line = line.rstrip()
2920
# cpp-style string concatenation:
2921
if debug:
2922
self.progress("more partial line")
2923
line = re.sub(r'"\s*"', '', line)
2924
partial_line += line
2925
continue
2926
if debug:
2927
self.progress("found close-brace")
2928
message_infos.append(partial_line + m.group(1))
2929
linestate = linestate_none
2930
continue
2931
raise NotAchievedException("Bad line (%s)")
2932
2933
if linestate != linestate_none:
2934
raise NotAchievedException("Must be linestate-none at end of file")
2935
2936
# now look in the vehicle-specific logfile:
2937
filepath = os.path.join(self.vehicle_code_dirpath(), "Log.cpp")
2938
state_outside = 67
2939
state_inside = 68
2940
state = state_outside
2941
linestate_none = 89
2942
linestate_within = 90
2943
linestate = linestate_none
2944
for line in open(filepath, 'rb').readlines():
2945
if isinstance(line, bytes):
2946
line = line.decode("utf-8")
2947
line = re.sub("//.*", "", line) # trim comments
2948
if re.match(r"\s*$", line):
2949
# blank line
2950
continue
2951
if state == state_outside:
2952
if ("const LogStructure" in line or
2953
"const struct LogStructure" in line):
2954
state = state_inside
2955
continue
2956
if state == state_inside:
2957
if re.match("};", line):
2958
state = state_outside
2959
break
2960
if linestate == linestate_none:
2961
if "#if HAL_QUADPLANE_ENABLED" in line:
2962
continue
2963
if "#if FRAME_CONFIG == HELI_FRAME" in line:
2964
continue
2965
if "#if AC_PRECLAND_ENABLED" in line:
2966
continue
2967
if "#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED" in line:
2968
continue
2969
if "#end" in line:
2970
continue
2971
if "LOG_COMMON_STRUCTURES" in line:
2972
continue
2973
m = re.match(r"\s*{(.*)},\s*", line)
2974
if m is not None:
2975
# complete line
2976
# print("Complete line: %s" % str(line))
2977
message_infos.append(m.group(1))
2978
continue
2979
m = re.match(r"\s*{(.*)", line)
2980
if m is None:
2981
raise NotAchievedException("Bad line %s" % line)
2982
partial_line = m.group(1)
2983
linestate = linestate_within
2984
continue
2985
if linestate == linestate_within:
2986
m = re.match("(.*)}", line)
2987
if m is None:
2988
line = line.rstrip()
2989
newline = re.sub(r"\\$", "", line)
2990
if newline == line:
2991
raise NotAchievedException("Expected backslash at end of line")
2992
line = newline
2993
line = line.rstrip()
2994
# cpp-style string concatenation:
2995
line = re.sub(r'"\s*"', '', line)
2996
partial_line += line
2997
continue
2998
message_infos.append(partial_line + m.group(1))
2999
linestate = linestate_none
3000
continue
3001
raise NotAchievedException("Bad line (%s)")
3002
3003
if state == state_inside:
3004
raise NotAchievedException("Should not be in state_inside at end")
3005
3006
for message_info in message_infos:
3007
print("message_info: %s" % str(message_info))
3008
for define in defines:
3009
message_info = re.sub(define, defines[define], message_info)
3010
m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*(true|false))?\s*$', message_info) # noqa
3011
if m is None:
3012
print("NO MATCH")
3013
continue
3014
(name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5))
3015
if name in ids:
3016
raise NotAchievedException("Already seen a (%s) message" % name)
3017
ids[name] = {
3018
"name": name,
3019
"format": fmt,
3020
"labels": labels,
3021
"units": units,
3022
"multipliers": multipliers,
3023
}
3024
3025
# now look for Log_Write(...) messages:
3026
base_directories = [
3027
os.path.join(self.rootdir(), 'libraries'),
3028
self.vehicle_code_dirpath(),
3029
]
3030
log_write_statements = []
3031
for base_directory in base_directories:
3032
for root, dirs, files in os.walk(base_directory):
3033
state_outside = 37
3034
state_inside = 38
3035
state = state_outside
3036
for f in files:
3037
if not re.search("[.]cpp$", f):
3038
continue
3039
filepath = os.path.join(root, f)
3040
if "AP_Logger/examples" in filepath:
3041
# this is the sample file which contains examples...
3042
continue
3043
count = 0
3044
for line in open(filepath, 'rb').readlines():
3045
if isinstance(line, bytes):
3046
line = line.decode("utf-8")
3047
if state == state_outside:
3048
if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or
3049
re.match(r"\s*logger[.]Write(?:Streaming)?\(", line)):
3050
state = state_inside
3051
line = re.sub("//.*", "", line) # trim comments
3052
log_write_statement = line
3053
continue
3054
if state == state_inside:
3055
line = re.sub("//.*", "", line) # trim comments
3056
# cpp-style string concatenation:
3057
line = re.sub(r'"\s*"', '', line)
3058
log_write_statement += line
3059
if re.match(r".*\);", line):
3060
log_write_statements.append(log_write_statement)
3061
state = state_outside
3062
count += 1
3063
if state != state_outside:
3064
raise NotAchievedException("Expected to be outside at end of file")
3065
# print("%s has %u lines" % (f, count))
3066
# change all whitespace to single space
3067
log_write_statements = [re.sub(r"\s+", " ", x) for x in log_write_statements]
3068
# print("Got log-write-statements: %s" % str(log_write_statements))
3069
results = []
3070
for log_write_statement in log_write_statements:
3071
for define in defines:
3072
log_write_statement = re.sub(define, defines[define], log_write_statement)
3073
# fair warning: order is important here because of the
3074
# NKT/XKT special case below....
3075
my_re = r' logger[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
3076
m = re.match(my_re, log_write_statement)
3077
if m is None:
3078
my_re = r' AP::logger\(\)[.]Write(?:Streaming)?\(\s*"(\w+)"\s*,\s*"([\w,]+)".*\);'
3079
m = re.match(my_re, log_write_statement)
3080
if m is None:
3081
raise NotAchievedException("Did not match (%s) with (%s)" % (log_write_statement, str(my_re)))
3082
else:
3083
results.append((m.group(1), m.group(2)))
3084
3085
for result in results:
3086
(name, labels) = result
3087
if name in ids:
3088
raise Exception("Already have id for (%s)" % name)
3089
# self.progress("Adding Log_Write result (%s)" % name)
3090
ids[name] = {
3091
"name": name,
3092
"labels": labels,
3093
}
3094
3095
if len(ids) == 0:
3096
raise NotAchievedException("Did not get any ids")
3097
3098
return ids
3099
3100
def LoggerDocumentation(self):
3101
'''Test Onboard Logging Generation'''
3102
xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml")
3103
parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py')
3104
try:
3105
os.unlink(xml_filepath)
3106
except OSError:
3107
pass
3108
vehicle = self.log_name()
3109
if vehicle == 'BalanceBot':
3110
# same binary and parameters as Rover
3111
return
3112
vehicle_map = {
3113
"ArduCopter": "Copter",
3114
"HeliCopter": "Copter",
3115
"ArduPlane": "Plane",
3116
"QuadPlane": "Plane",
3117
"Rover": "Rover",
3118
"AntennaTracker": "Tracker",
3119
"ArduSub": "Sub",
3120
}
3121
vehicle = vehicle_map[vehicle]
3122
3123
cmd = [parse_filepath, '--vehicle', vehicle]
3124
# cmd.append("--verbose")
3125
if util.run_cmd(cmd, directory=self.buildlogs_dirpath()) != 0:
3126
self.progress("Failed parse.py (%s)" % vehicle)
3127
return False
3128
length = os.path.getsize(xml_filepath)
3129
min_length = 1024
3130
if length < min_length:
3131
raise NotAchievedException("short xml file (%u < %u)" %
3132
(length, min_length))
3133
self.progress("xml file length is %u" % length)
3134
3135
from lxml import objectify
3136
xml = open(xml_filepath, 'rb').read()
3137
objectify.enable_recursive_str()
3138
tree = objectify.fromstring(xml)
3139
3140
# we allow for no docs for replay messages, as these are not for end-users. They are
3141
# effectively binary blobs for replay
3142
REPLAY_MSGS = ['RFRH', 'RFRF', 'REV2', 'RSO2', 'RWA2', 'REV3', 'RSO3', 'RWA3', 'RMGI',
3143
'REY3', 'RFRN', 'RISH', 'RISI', 'RISJ', 'RBRH', 'RBRI', 'RRNH', 'RRNI',
3144
'RGPH', 'RGPI', 'RGPJ', 'RASH', 'RASI', 'RBCH', 'RBCI', 'RVOH', 'RMGH',
3145
'ROFH', 'REPH', 'REVH', 'RWOH', 'RBOH', 'RSLL']
3146
3147
docco_ids = {}
3148
for thing in tree.logformat:
3149
name = str(thing.get("name"))
3150
docco_ids[name] = {
3151
"name": name,
3152
"labels": [],
3153
}
3154
if getattr(thing.fields, 'field', None) is None:
3155
if name in REPLAY_MSGS:
3156
continue
3157
raise NotAchievedException("no doc fields for %s" % name)
3158
for field in thing.fields.field:
3159
# print("field: (%s)" % str(field))
3160
fieldname = field.get("name")
3161
# print("Got (%s.%s)" % (name,str(fieldname)))
3162
docco_ids[name]["labels"].append(fieldname)
3163
3164
code_ids = self.all_log_format_ids()
3165
# self.progress("Code ids: (%s)" % str(sorted(code_ids.keys())))
3166
# self.progress("Docco ids: (%s)" % str(sorted(docco_ids.keys())))
3167
3168
for name in sorted(code_ids.keys()):
3169
if name not in docco_ids:
3170
self.progress("Undocumented message: %s" % str(name))
3171
continue
3172
seen_labels = {}
3173
for label in code_ids[name]["labels"].split(","):
3174
if label in seen_labels:
3175
raise NotAchievedException("%s.%s is duplicate label" %
3176
(name, label))
3177
seen_labels[label] = True
3178
if label not in docco_ids[name]["labels"]:
3179
raise NotAchievedException("%s.%s not in documented fields (have (%s))" %
3180
(name, label, ",".join(docco_ids[name]["labels"])))
3181
missing = []
3182
for name in sorted(docco_ids):
3183
if name not in code_ids and name not in REPLAY_MSGS:
3184
missing.append(name)
3185
continue
3186
for label in docco_ids[name]["labels"]:
3187
if label not in code_ids[name]["labels"].split(","):
3188
# "name" was found in the XML, so was found in an
3189
# @LoggerMessage markup line, but was *NOT* found
3190
# in our bodgy parsing of the C++ code (in a
3191
# Log_Write call or in the static structures
3192
raise NotAchievedException("documented field %s.%s not found in code" %
3193
(name, label))
3194
if len(missing) > 0:
3195
raise NotAchievedException("Documented messages (%s) not in code" % missing)
3196
3197
def initialise_after_reboot_sitl(self):
3198
3199
# after reboot stream-rates may be zero. Request streams.
3200
self.drain_mav()
3201
self.wait_heartbeat()
3202
self.set_streamrate(self.sitl_streamrate())
3203
self.progress("Reboot complete")
3204
3205
def customise_SITL_commandline(self,
3206
customisations,
3207
model=None,
3208
defaults_filepath=None,
3209
wipe=False,
3210
set_streamrate_callback=None,
3211
binary=None):
3212
'''customisations could be "--serial5=sim:nmea" '''
3213
self.contexts[-1].sitl_commandline_customised = True
3214
self.mav.close()
3215
self.stop_SITL()
3216
self.start_SITL(binary=binary,
3217
model=model,
3218
defaults_filepath=defaults_filepath,
3219
customisations=customisations,
3220
wipe=wipe)
3221
self.mav.do_connect()
3222
tstart = time.time()
3223
while True:
3224
if time.time() - tstart > 30:
3225
raise NotAchievedException("Failed to customise")
3226
try:
3227
m = self.wait_heartbeat(drain_mav=True)
3228
if m.type == 0:
3229
self.progress("Bad heartbeat: %s" % str(m))
3230
continue
3231
except IOError:
3232
pass
3233
break
3234
if set_streamrate_callback is not None:
3235
set_streamrate_callback()
3236
else:
3237
self.set_streamrate(self.sitl_streamrate())
3238
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=15)
3239
if m is None:
3240
raise NotAchievedException("No RC_CHANNELS message after restarting SITL")
3241
3242
# stash our arguments in case we need to preserve them in
3243
# reboot_sitl with Valgrind active:
3244
if self.valgrind or self.callgrind:
3245
self.valgrind_restart_model = model
3246
self.valgrind_restart_defaults_filepath = defaults_filepath
3247
self.valgrind_restart_customisations = customisations
3248
3249
def default_parameter_list(self):
3250
ret = {
3251
'LOG_DISARMED': 1,
3252
# also lower logging rate to reduce log sizes
3253
'LOG_DARM_RATEMAX': 5,
3254
'LOG_FILE_RATEMAX': 10,
3255
}
3256
if self.force_ahrs_type is not None:
3257
if self.force_ahrs_type == 2:
3258
ret["EK2_ENABLE"] = 1
3259
if self.force_ahrs_type == 3:
3260
ret["EK3_ENABLE"] = 1
3261
ret["AHRS_EKF_TYPE"] = self.force_ahrs_type
3262
if self.num_aux_imus > 0:
3263
ret["SIM_IMU_COUNT"] = self.num_aux_imus + 3
3264
if self.replay:
3265
ret["LOG_REPLAY"] = 1
3266
return ret
3267
3268
def apply_default_parameter_list(self):
3269
self.set_parameters(self.default_parameter_list())
3270
3271
def apply_default_parameters(self):
3272
self.apply_defaultfile_parameters()
3273
self.apply_default_parameter_list()
3274
self.reboot_sitl()
3275
3276
def reset_SITL_commandline(self):
3277
self.progress("Resetting SITL commandline to default")
3278
self.stop_SITL()
3279
try:
3280
del self.valgrind_restart_customisations
3281
except Exception:
3282
pass
3283
self.start_SITL(wipe=True)
3284
self.set_streamrate(self.sitl_streamrate())
3285
self.apply_default_parameters()
3286
self.progress("Reset SITL commandline to default")
3287
3288
def pause_SITL(self):
3289
'''temporarily stop the SITL process from running. Note that
3290
simulation time will not move forward!'''
3291
# self.progress("Pausing SITL")
3292
self.sitl.kill(signal.SIGSTOP)
3293
3294
def unpause_SITL(self):
3295
# self.progress("Unpausing SITL")
3296
self.sitl.kill(signal.SIGCONT)
3297
3298
def stop_SITL(self):
3299
self.progress("Stopping SITL")
3300
self.expect_list_remove(self.sitl)
3301
util.pexpect_close(self.sitl)
3302
self.sitl = None
3303
3304
def start_test(self, description):
3305
self.progress("##################################################################################")
3306
self.progress("########## %s ##########" % description)
3307
self.progress("##################################################################################")
3308
3309
def try_symlink_tlog(self):
3310
self.buildlog = self.buildlogs_path(self.log_name() + "-test.tlog")
3311
self.progress("buildlog=%s" % self.buildlog)
3312
if os.path.exists(self.buildlog):
3313
os.unlink(self.buildlog)
3314
try:
3315
os.link(self.logfile, self.buildlog)
3316
except OSError as error:
3317
self.progress("OSError [%d]: %s" % (error.errno, error.strerror))
3318
self.progress("Problem: Failed to create link: %s => %s, "
3319
"will copy tlog manually to target location" %
3320
(self.logfile, self.buildlog))
3321
self.copy_tlog = True
3322
3323
#################################################
3324
# GENERAL UTILITIES
3325
#################################################
3326
def expect_list_clear(self):
3327
"""clear the expect list."""
3328
for p in self.expect_list[:]:
3329
self.expect_list.remove(p)
3330
3331
def expect_list_extend(self, list_to_add):
3332
"""Extend the expect list."""
3333
self.expect_list.extend(list_to_add)
3334
3335
def expect_list_add(self, item):
3336
"""Extend the expect list."""
3337
self.expect_list.extend([item])
3338
3339
def expect_list_remove(self, item):
3340
"""Remove item from the expect list."""
3341
self.expect_list.remove(item)
3342
3343
def heartbeat_interval_ms(self):
3344
c = self.context_get()
3345
if c is None:
3346
return 1000
3347
return c.heartbeat_interval_ms
3348
3349
def set_heartbeat_interval_ms(self, interval_ms):
3350
c = self.context_get()
3351
if c is None:
3352
raise ValueError("No context")
3353
if c.original_heartbeat_interval_ms is None:
3354
c.original_heartbeat_interval_ms = c.heartbeat_interval_ms
3355
c.heartbeat_interval_ms = interval_ms
3356
3357
def set_heartbeat_rate(self, rate_hz):
3358
if rate_hz == 0:
3359
self.set_heartbeat_interval_ms(None)
3360
return
3361
self.set_heartbeat_interval_ms(1000.0/rate_hz)
3362
3363
def do_heartbeats(self, force=False):
3364
# self.progress("do_heartbeats")
3365
if self.heartbeat_interval_ms() is None and not force:
3366
return
3367
x = self.mav.messages.get("SYSTEM_TIME", None)
3368
now_wc = time.time()
3369
if (force or
3370
x is None or
3371
self.last_heartbeat_time_ms is None or
3372
self.last_heartbeat_time_ms < x.time_boot_ms or
3373
x.time_boot_ms - self.last_heartbeat_time_ms > self.heartbeat_interval_ms() or
3374
now_wc - self.last_heartbeat_time_wc_s > 1):
3375
if x is not None:
3376
self.last_heartbeat_time_ms = x.time_boot_ms
3377
self.last_heartbeat_time_wc_s = now_wc
3378
self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_GCS,
3379
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
3380
0,
3381
0,
3382
0)
3383
3384
def drain_all_pexpects(self):
3385
for p in self.expect_list:
3386
util.pexpect_drain(p)
3387
3388
def idle_hook(self, mav):
3389
"""Called when waiting for a mavlink message."""
3390
if self.in_drain_mav:
3391
return
3392
self.drain_all_pexpects()
3393
3394
class MessageHook():
3395
'''base class for objects that watch the message stream and check for
3396
validity of fields'''
3397
def __init__(self, suite):
3398
self.suite = suite
3399
3400
def process(self):
3401
pass
3402
3403
def progress_prefix(self):
3404
return ""
3405
3406
def progress(self, string):
3407
string = self.progress_prefix() + string
3408
self.suite.progress(string)
3409
3410
class ValidateIntPositionAgainstSimState(MessageHook):
3411
'''monitors a message containing a position containing lat/lng in 1e7,
3412
makes sure it stays close to SIMSTATE'''
3413
def __init__(self, suite, other_int_message_name, max_allowed_divergence=150):
3414
super(TestSuite.ValidateIntPositionAgainstSimState, self).__init__(suite)
3415
self.other_int_message_name = other_int_message_name
3416
self.max_allowed_divergence = max_allowed_divergence
3417
self.max_divergence = 0
3418
self.gpi = None
3419
self.simstate = None
3420
self.last_print = 0
3421
self.min_print_interval = 1 # seconds
3422
3423
def progress_prefix(self):
3424
return "VIPASS: "
3425
3426
def process(self, mav, m):
3427
if m.get_type() == self.other_int_message_name:
3428
self.gpi = m
3429
elif m.get_type() == 'SIMSTATE':
3430
self.simstate = m
3431
if self.gpi is None:
3432
return
3433
if self.simstate is None:
3434
return
3435
3436
divergence = self.suite.get_distance_int(self.gpi, self.simstate)
3437
if (time.time() - self.last_print > self.min_print_interval or
3438
divergence > self.max_divergence):
3439
self.progress(f"distance(SIMSTATE,{self.other_int_message_name})={divergence:.5f}m")
3440
self.last_print = time.time()
3441
if divergence > self.max_divergence:
3442
self.max_divergence = divergence
3443
if divergence > self.max_allowed_divergence:
3444
raise NotAchievedException(
3445
"%s diverged from simstate by %fm (max=%fm" %
3446
(self.other_int_message_name, divergence, self.max_allowed_divergence,))
3447
3448
def hook_removed(self):
3449
self.progress(f"Maximum divergence was {self.max_divergence}m (max={self.max_allowed_divergence}m)")
3450
3451
class ValidateGlobalPositionIntAgainstSimState(ValidateIntPositionAgainstSimState):
3452
def __init__(self, suite, **kwargs):
3453
super(TestSuite.ValidateGlobalPositionIntAgainstSimState, self).__init__(suite, 'GLOBAL_POSITION_INT', **kwargs)
3454
3455
class ValidateAHRS3AgainstSimState(ValidateIntPositionAgainstSimState):
3456
def __init__(self, suite, **kwargs):
3457
super(TestSuite.ValidateAHRS3AgainstSimState, self).__init__(suite, 'AHRS3', **kwargs)
3458
3459
def message_hook(self, mav, msg):
3460
"""Called as each mavlink msg is received."""
3461
# print("msg: %s" % str(msg))
3462
if msg.get_type() == 'STATUSTEXT':
3463
self.progress("AP: %s" % msg.text, send_statustext=False)
3464
3465
self.write_msg_to_tlog(msg)
3466
3467
self.idle_hook(mav)
3468
self.do_heartbeats()
3469
3470
for h in self.message_hooks:
3471
if isinstance(h, TestSuite.MessageHook):
3472
h.process(mav, msg)
3473
continue
3474
# assume it's a function
3475
h(mav, msg)
3476
3477
def send_message_hook(self, msg, x):
3478
self.write_msg_to_tlog(msg)
3479
3480
def write_msg_to_tlog(self, msg):
3481
usec = int(time.time() * 1.0e6)
3482
if self.tlog is None:
3483
tlog_filename = "autotest-%u.tlog" % usec
3484
self.tlog = open(tlog_filename, 'wb')
3485
3486
content = bytearray(struct.pack('>Q', usec) + msg.get_msgbuf())
3487
self.tlog.write(content)
3488
3489
def expect_callback(self, e):
3490
"""Called when waiting for a expect pattern."""
3491
for p in self.expect_list:
3492
if p == e:
3493
continue
3494
util.pexpect_drain(p)
3495
self.drain_mav(quiet=True)
3496
self.do_heartbeats()
3497
3498
def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False):
3499
'''drain all data on mavlink connection mav (defaulting to self.mav).
3500
It is assumed that this connection is connected to the normal
3501
simulation.'''
3502
if mav is None:
3503
mav = self.mav
3504
count = 0
3505
tstart = time.time()
3506
self.pause_SITL()
3507
# sometimes we recv() when the process is likely to go away..
3508
old_autoreconnect = mav.autoreconnect
3509
mav.autoreconnect = False
3510
while True:
3511
try:
3512
this = mav.recv(1000000)
3513
except Exception:
3514
mav.autoreconnect = old_autoreconnect
3515
self.unpause_SITL()
3516
raise
3517
if len(this) == 0:
3518
break
3519
count += len(this)
3520
mav.autoreconnect = old_autoreconnect
3521
self.unpause_SITL()
3522
if quiet:
3523
return
3524
tdelta = time.time() - tstart
3525
if tdelta == 0:
3526
rate = "instantly"
3527
else:
3528
rate = "%f/s" % (count/float(tdelta),)
3529
self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate), send_statustext=False)
3530
if freshen_sim_time:
3531
self.get_sim_time()
3532
3533
def drain_mav(self, mav=None, unparsed=False, quiet=True):
3534
'''parse all data available on connection mav (defaulting to
3535
self.mav). It is assumed that mav is connected to the normal
3536
simulation'''
3537
if unparsed:
3538
return self.drain_mav_unparsed(quiet=quiet, mav=mav)
3539
if mav is None:
3540
mav = self.mav
3541
self.in_drain_mav = True
3542
count = 0
3543
tstart = time.time()
3544
timeout = 120
3545
failed_to_drain = False
3546
self.pause_SITL()
3547
# sometimes we recv() when the process is likely to go away..
3548
old_autoreconnect = mav.autoreconnect
3549
mav.autoreconnect = False
3550
while True:
3551
try:
3552
receive_result = mav.recv_msg()
3553
except Exception:
3554
mav.autoreconnect = True
3555
self.unpause_SITL()
3556
raise
3557
if receive_result is None:
3558
break
3559
count += 1
3560
if time.time() - tstart > timeout:
3561
# ArduPilot can produce messages faster than we can
3562
# consume them. Until a better solution is found,
3563
# just die if that seems to be the case:
3564
failed_to_drain = True
3565
quiet = False
3566
mav.autoreconnect = old_autoreconnect
3567
self.unpause_SITL()
3568
if quiet:
3569
self.in_drain_mav = False
3570
return
3571
tdelta = time.time() - tstart
3572
if tdelta == 0:
3573
rate = "instantly"
3574
else:
3575
rate = "%f/s" % (count/float(tdelta),)
3576
3577
if not quiet:
3578
self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False)
3579
3580
if failed_to_drain:
3581
raise NotAchievedException("Did not fully drain MAV within %ss" % timeout)
3582
3583
self.in_drain_mav = False
3584
3585
def do_timesync_roundtrip(self, quiet=False, timeout_in_wallclock=False):
3586
if not quiet:
3587
self.progress("Doing timesync roundtrip")
3588
if timeout_in_wallclock:
3589
tstart = time.time()
3590
else:
3591
tstart = self.get_sim_time()
3592
self.mav.mav.timesync_send(0, self.timesync_number * 1000 + self.mav.source_system)
3593
while True:
3594
if timeout_in_wallclock:
3595
now = time.time()
3596
else:
3597
now = self.get_sim_time_cached()
3598
if now - tstart > 5:
3599
raise AutoTestTimeoutException("Did not get timesync response")
3600
m = self.mav.recv_match(type='TIMESYNC', blocking=True, timeout=1)
3601
if not quiet:
3602
self.progress("Received: %s" % str(m))
3603
if m is None:
3604
continue
3605
if m.ts1 % 1000 != self.mav.source_system:
3606
self.progress("this isn't a response to our timesync (%s)" % (m.ts1 % 1000))
3607
continue
3608
if m.tc1 == 0:
3609
# this should also not happen:
3610
self.progress("this is a timesync request, which we don't answer")
3611
continue
3612
if int(m.ts1 / 1000) != self.timesync_number:
3613
self.progress("this isn't the one we just sent")
3614
continue
3615
if m.get_srcSystem() != self.mav.target_system:
3616
self.progress("response from system other than our target (want=%u got=%u" %
3617
(self.mav.target_system, m.get_srcSystem()))
3618
continue
3619
# no component check ATM because we send broadcast...
3620
# if m.get_srcComponent() != self.mav.target_component:
3621
# self.progress("response from component other than our target (got=%u want=%u)" % (m.get_srcComponent(), self.mav.target_component)) # noqa
3622
# continue
3623
if not quiet:
3624
self.progress("Received TIMESYNC response after %fs" % (now - tstart))
3625
self.timesync_number += 1
3626
break
3627
3628
def log_filepath(self, lognum):
3629
'''return filepath to lognum (where lognum comes from LOG_ENTRY'''
3630
log_list = self.log_list()
3631
return log_list[lognum-1]
3632
3633
def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):
3634
tocheck = len(bytes1)
3635
if maxlen is not None:
3636
if tocheck > maxlen:
3637
tocheck = maxlen
3638
for i in range(0, tocheck):
3639
if bytes1[i] != bytes2[i]:
3640
raise NotAchievedException("differ at offset %u" % i)
3641
3642
def HIGH_LATENCY2(self):
3643
'''test sending of HIGH_LATENCY2'''
3644
3645
# set airspeed sensor type to DLVR for air temperature message testing
3646
if not self.is_plane():
3647
# Plane does not have enable parameter
3648
self.set_parameter("ARSPD_ENABLE", 1)
3649
self.set_parameter("ARSPD_BUS", 2)
3650
self.set_parameter("ARSPD_TYPE", 7)
3651
self.reboot_sitl()
3652
3653
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True, verbose=True, timeout=30)
3654
3655
# should not be getting HIGH_LATENCY2 by default
3656
m = self.mav.recv_match(type='HIGH_LATENCY2', blocking=True, timeout=2)
3657
if m is not None:
3658
raise NotAchievedException("Shouldn't be getting HIGH_LATENCY2 by default")
3659
m = self.poll_message("HIGH_LATENCY2")
3660
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) != 0:
3661
raise NotAchievedException("Expected GPS to be OK")
3662
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, True, True, True)
3663
self.set_parameter("SIM_GPS1_TYPE", 0)
3664
self.delay_sim_time(10)
3665
self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS, False, False, False)
3666
m = self.poll_message("HIGH_LATENCY2")
3667
self.progress(self.dump_message_verbose(m))
3668
if (m.failure_flags & mavutil.mavlink.HL_FAILURE_FLAG_GPS) == 0:
3669
raise NotAchievedException("Expected GPS to be failed")
3670
3671
self.start_subtest("HIGH_LATENCY2 location")
3672
self.set_parameter("SIM_GPS1_TYPE", 1)
3673
self.delay_sim_time(10)
3674
m = self.poll_message("HIGH_LATENCY2")
3675
self.progress(self.dump_message_verbose(m))
3676
loc = mavutil.location(m.latitude, m.longitude, m.altitude, 0)
3677
dist = self.get_distance_int(loc, self.sim_location_int())
3678
3679
if dist > 1:
3680
raise NotAchievedException("Bad location from HIGH_LATENCY2")
3681
3682
self.start_subtest("HIGH_LATENCY2 Air Temperature")
3683
m = self.poll_message("HIGH_LATENCY2")
3684
mavutil.dump_message_verbose(sys.stdout, m)
3685
3686
if m.temperature_air == -128: # High_Latency2 defaults to INT8_MIN for no temperature available
3687
raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2")
3688
self.HIGH_LATENCY2_links()
3689
3690
def context_set_message_rate_hz(self, id, rate_hz, run_cmd=None):
3691
if run_cmd is None:
3692
run_cmd = self.run_cmd
3693
3694
overridden_message_rates = self.context_get().overridden_message_rates
3695
3696
if id not in overridden_message_rates:
3697
overridden_message_rates[id] = self.measure_message_rate(id)
3698
3699
self.set_message_rate_hz(id, rate_hz, run_cmd=run_cmd)
3700
3701
def HIGH_LATENCY2_links(self):
3702
3703
self.start_subtest("SerialProtocol_MAVLinkHL links")
3704
3705
ex = None
3706
self.context_push()
3707
mav2 = None
3708
try:
3709
3710
self.set_parameter("SERIAL2_PROTOCOL", 43) # HL)
3711
3712
self.reboot_sitl()
3713
3714
mav2 = mavutil.mavlink_connection(
3715
"tcp:localhost:%u" % self.adjust_ardupilot_port(5763),
3716
robust_parsing=True,
3717
source_system=7,
3718
source_component=7,
3719
)
3720
3721
self.start_subsubtest("Don't get HIGH_LATENCY2 by default")
3722
for mav in self.mav, mav2:
3723
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav, timeout=10)
3724
3725
self.start_subsubtest("Get HIGH_LATENCY2 upon link enabled only on HL link")
3726
for run_cmd in self.run_cmd, self.run_cmd_int:
3727
self.run_cmd_enable_high_latency(True, run_cmd=run_cmd)
3728
self.assert_receive_message("HIGH_LATENCY2", mav=mav2, timeout=10)
3729
self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)
3730
3731
self.start_subsubtest("Not get HIGH_LATENCY2 upon HL disable")
3732
self.run_cmd_enable_high_latency(False, run_cmd=run_cmd)
3733
self.delay_sim_time(10)
3734
self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)
3735
self.drain_mav(mav2)
3736
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)
3737
3738
self.start_subsubtest("Stream rate adjustments")
3739
self.run_cmd_enable_high_latency(True)
3740
self.assert_message_rate_hz("HIGH_LATENCY2", 0.2, ndigits=1, mav=mav2, sample_period=60)
3741
for test_rate in (1, 0.1, 2):
3742
self.test_rate(
3743
"HIGH_LATENCY2 on enabled link",
3744
test_rate,
3745
test_rate,
3746
mav=mav2,
3747
ndigits=1,
3748
victim_message="HIGH_LATENCY2",
3749
message_rate_sample_period=60,
3750
)
3751
self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10)
3752
self.run_cmd_enable_high_latency(False)
3753
3754
self.start_subsubtest("Not get HIGH_LATENCY2 after disabling after playing with rates")
3755
self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10)
3756
self.delay_sim_time(1)
3757
self.drain_mav(mav2)
3758
self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10)
3759
3760
self.start_subsubtest("Enable and disable should not affect non-HL links getting HIGH_LATENCY2")
3761
self.set_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3762
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3763
3764
self.run_cmd_enable_high_latency(True)
3765
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav),
3766
3767
self.run_cmd_enable_high_latency(False)
3768
self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav)
3769
except Exception as e:
3770
self.print_exception_caught(e)
3771
ex = e
3772
3773
self.context_pop()
3774
3775
self.reboot_sitl()
3776
3777
self.set_message_rate_hz("HIGH_LATENCY2", 0)
3778
3779
if ex is not None:
3780
raise ex
3781
3782
def download_full_log_list(self, print_logs=True):
3783
tstart = self.get_sim_time()
3784
self.mav.mav.log_request_list_send(self.sysid_thismav(),
3785
1, # target component
3786
0,
3787
0xffff)
3788
logs = {}
3789
last_id = None
3790
num_logs = None
3791
while True:
3792
now = self.get_sim_time_cached()
3793
if now - tstart > 5:
3794
raise NotAchievedException("Did not download list")
3795
m = self.mav.recv_match(type='LOG_ENTRY',
3796
blocking=True,
3797
timeout=1)
3798
if print_logs:
3799
self.progress("Received (%s)" % str(m))
3800
if m is None:
3801
continue
3802
logs[m.id] = m
3803
if last_id is None:
3804
if m.num_logs == 0:
3805
# caller to guarantee this works:
3806
raise NotAchievedException("num_logs is zero")
3807
num_logs = m.num_logs
3808
else:
3809
if m.id != last_id + 1:
3810
raise NotAchievedException("Sequence not increasing")
3811
if m.num_logs != num_logs:
3812
raise NotAchievedException("Number of logs changed")
3813
if m.time_utc < 1000 and m.id != m.num_logs:
3814
raise NotAchievedException("Bad timestamp")
3815
if m.id != m.last_log_num:
3816
if m.size == 0:
3817
raise NotAchievedException("Zero-sized log")
3818
last_id = m.id
3819
if m.id == m.last_log_num:
3820
self.progress("Got all logs")
3821
break
3822
3823
# ensure we don't get any extras:
3824
m = self.mav.recv_match(type='LOG_ENTRY',
3825
blocking=True,
3826
timeout=2)
3827
if m is not None:
3828
raise NotAchievedException("Received extra LOG_ENTRY?!")
3829
return logs
3830
3831
def TestLogDownloadWrap(self):
3832
"""Test log wrapping."""
3833
if self.is_tracker():
3834
# tracker starts armed, which is annoying
3835
return
3836
self.progress("Ensuring we have contents we care about")
3837
self.set_parameter("LOG_FILE_DSRMROT", 1)
3838
self.set_parameter("LOG_DISARMED", 0)
3839
self.reboot_sitl()
3840
logspath = Path("logs")
3841
3842
def create_num_logs(num_logs, logsdir, clear_logsdir=True):
3843
if clear_logsdir:
3844
shutil.rmtree(logsdir, ignore_errors=True)
3845
logsdir.mkdir()
3846
lastlogfile_path = logsdir / Path("LASTLOG.TXT")
3847
self.progress(f"Add LASTLOG.TXT file with counter at {num_logs}")
3848
with open(lastlogfile_path, 'w') as lastlogfile:
3849
lastlogfile.write(f"{num_logs}\n")
3850
self.progress(f"Create fakelogs from 1 to {num_logs} on logs directory")
3851
for ii in range(1, num_logs + 1):
3852
new_log = logsdir / Path(f"{str(ii).zfill(8)}.BIN")
3853
with open(new_log, 'w+') as logfile:
3854
logfile.write(f"I AM LOG {ii}\n")
3855
logfile.write('1' * ii)
3856
3857
def verify_logs(test_log_num):
3858
try:
3859
wrap = False
3860
offset = 0
3861
max_logs_num = int(self.get_parameter("LOG_MAX_FILES"))
3862
if test_log_num > max_logs_num:
3863
wrap = True
3864
offset = test_log_num - max_logs_num
3865
test_log_num = max_logs_num
3866
logs_dict = self.download_full_log_list(print_logs=False)
3867
if len(logs_dict) != test_log_num:
3868
raise NotAchievedException(
3869
f"Didn't get the full log list, expect {test_log_num} got {len(logs_dict)}")
3870
self.progress("Checking logs size are matching")
3871
start_log = offset if wrap else 1
3872
for ii in range(start_log, test_log_num + 1 - offset):
3873
log_i = logspath / Path(f"{str(ii + offset).zfill(8)}.BIN")
3874
if logs_dict[ii].size != log_i.stat().st_size:
3875
logs_dict = self.download_full_log_list(print_logs=False)
3876
# sometimes we don't have finish writing the log, so get it again prevent failure
3877
if logs_dict[ii].size != log_i.stat().st_size:
3878
raise NotAchievedException(
3879
f"Log{ii} size mismatch : {logs_dict[ii].size} vs {log_i.stat().st_size}"
3880
)
3881
if wrap:
3882
self.progress("Checking wrapped logs size are matching")
3883
for ii in range(1, offset):
3884
log_i = logspath / Path(f"{str(ii).zfill(8)}.BIN")
3885
if logs_dict[test_log_num + 1 - offset + ii].size != log_i.stat().st_size:
3886
self.progress(f"{logs_dict[test_log_num + 1 - offset + ii]}")
3887
raise NotAchievedException(
3888
f"Log{test_log_num + 1 - offset + ii} size mismatch :"
3889
f" {logs_dict[test_log_num + 1 - offset + ii].size} vs {log_i.stat().st_size}"
3890
)
3891
except NotAchievedException as e:
3892
shutil.rmtree(logspath, ignore_errors=True)
3893
logspath.mkdir()
3894
with open(logspath / Path("LASTLOG.TXT"), 'w') as lastlogfile:
3895
lastlogfile.write("1\n")
3896
raise e
3897
3898
def add_and_verify_log(test_log_num):
3899
self.wait_ready_to_arm()
3900
self.arm_vehicle()
3901
self.delay_sim_time(1)
3902
self.disarm_vehicle()
3903
self.delay_sim_time(10)
3904
verify_logs(test_log_num + 1)
3905
3906
def create_and_verify_logs(test_log_num, clear_logsdir=True):
3907
self.progress(f"Test {test_log_num} logs")
3908
create_num_logs(test_log_num, logspath, clear_logsdir)
3909
self.reboot_sitl()
3910
verify_logs(test_log_num)
3911
self.start_subsubtest("Adding one more log")
3912
add_and_verify_log(test_log_num)
3913
3914
self.start_subtest("Checking log list match with filesystem info")
3915
create_and_verify_logs(500)
3916
create_and_verify_logs(10)
3917
create_and_verify_logs(1)
3918
3919
self.start_subtest("Change LOG_MAX_FILES and Checking log list match with filesystem info")
3920
self.set_parameter("LOG_MAX_FILES", 250)
3921
create_and_verify_logs(250)
3922
self.set_parameter("LOG_MAX_FILES", 1)
3923
create_and_verify_logs(1)
3924
3925
self.start_subtest("Change LOG_MAX_FILES, don't clear old logs and Checking log list match with filesystem info")
3926
self.set_parameter("LOG_MAX_FILES", 500)
3927
create_and_verify_logs(500)
3928
self.set_parameter("LOG_MAX_FILES", 250)
3929
create_and_verify_logs(250, clear_logsdir=False)
3930
3931
# cleanup
3932
shutil.rmtree(logspath, ignore_errors=True)
3933
3934
def TestLogDownload(self):
3935
"""Test Onboard Log Download."""
3936
if self.is_tracker():
3937
# tracker starts armed, which is annoying
3938
return
3939
self.progress("Ensuring we have contents we care about")
3940
self.set_parameter("LOG_FILE_DSRMROT", 1)
3941
self.set_parameter("LOG_DISARMED", 0)
3942
self.reboot_sitl()
3943
original_log_list = self.log_list()
3944
for i in range(0, 10):
3945
self.wait_ready_to_arm()
3946
self.arm_vehicle()
3947
self.delay_sim_time(1)
3948
self.disarm_vehicle()
3949
new_log_list = self.log_list()
3950
new_log_count = len(new_log_list) - len(original_log_list)
3951
if new_log_count != 10:
3952
raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" %
3953
(new_log_count, original_log_list, new_log_list))
3954
self.progress("Directory contents: %s" % str(new_log_list))
3955
3956
self.download_full_log_list()
3957
log_id = 5
3958
ofs = 6
3959
count = 2
3960
self.start_subtest("downloading %u bytes from offset %u from log_id %u" %
3961
(count, ofs, log_id))
3962
self.mav.mav.log_request_data_send(self.sysid_thismav(),
3963
1, # target component
3964
log_id,
3965
ofs,
3966
count)
3967
m = self.assert_receive_message('LOG_DATA', timeout=2)
3968
if m.ofs != ofs:
3969
raise NotAchievedException("Incorrect offset")
3970
if m.count != count:
3971
raise NotAchievedException("Did not get correct number of bytes")
3972
log_filepath = self.log_filepath(log_id)
3973
self.progress("Checking against log_filepath (%s)" % str(log_filepath))
3974
with open(log_filepath, "rb") as bob:
3975
bob.seek(ofs)
3976
actual_bytes = bob.read(2)
3977
actual_bytes = bytearray(actual_bytes)
3978
if m.data[0] != actual_bytes[0]:
3979
raise NotAchievedException("Bad first byte got=(0x%02x) want=(0x%02x)" %
3980
(m.data[0], actual_bytes[0]))
3981
if m.data[1] != actual_bytes[1]:
3982
raise NotAchievedException("Bad second byte")
3983
3984
log_id = 7
3985
log_filepath = self.log_filepath(log_id)
3986
self.start_subtest("Downloading log id %u (%s)" % (log_id, log_filepath))
3987
with open(log_filepath, "rb") as bob:
3988
actual_bytes = bytearray(bob.read())
3989
3990
# get the size first
3991
self.mav.mav.log_request_list_send(self.sysid_thismav(),
3992
1, # target component
3993
log_id,
3994
log_id)
3995
log_entry = self.assert_receive_message('LOG_ENTRY', timeout=2, verbose=True)
3996
if log_entry.size != len(actual_bytes):
3997
raise NotAchievedException("Incorrect bytecount")
3998
if log_entry.id != log_id:
3999
raise NotAchievedException("Incorrect log id received")
4000
4001
# download the log file in the normal way:
4002
bytes_to_fetch = 100000
4003
self.progress("Sending request for %u bytes at offset 0" % (bytes_to_fetch,))
4004
tstart = self.get_sim_time()
4005
self.mav.mav.log_request_data_send(
4006
self.sysid_thismav(),
4007
1, # target component
4008
log_id,
4009
0,
4010
bytes_to_fetch
4011
)
4012
bytes_to_read = bytes_to_fetch
4013
if log_entry.size < bytes_to_read:
4014
bytes_to_read = log_entry.size
4015
data_downloaded = []
4016
bytes_read = 0
4017
last_print = 0
4018
while True:
4019
if bytes_read >= bytes_to_read:
4020
break
4021
if self.get_sim_time_cached() - tstart > 120:
4022
raise NotAchievedException("Did not download log in good time")
4023
m = self.assert_receive_message('LOG_DATA', timeout=2)
4024
if m.ofs != bytes_read:
4025
raise NotAchievedException("Unexpected offset")
4026
if m.id != log_id:
4027
raise NotAchievedException("Unexpected id")
4028
if m.count == 0:
4029
raise NotAchievedException("Zero bytes read")
4030
data_downloaded.extend(m.data[0:m.count])
4031
bytes_read += m.count
4032
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4033
if time.time() - last_print > 10:
4034
last_print = time.time()
4035
self.progress("Read %u/%u" % (bytes_read, bytes_to_read))
4036
4037
self.progress("actual_bytes_len=%u data_downloaded_len=%u" %
4038
(len(actual_bytes), len(data_downloaded)))
4039
self.assert_bytes_equal(actual_bytes, data_downloaded, maxlen=bytes_to_read)
4040
4041
if False:
4042
bytes_to_read = log_entry.size
4043
bytes_read = 0
4044
data_downloaded = []
4045
while bytes_read < bytes_to_read:
4046
bytes_to_fetch = int(random.random() * 100)
4047
if bytes_to_fetch > 90:
4048
bytes_to_fetch = 90
4049
self.progress("Sending request for %u bytes at offset %u" % (bytes_to_fetch, bytes_read))
4050
self.mav.mav.log_request_data_send(
4051
self.sysid_thismav(),
4052
1, # target component
4053
log_id,
4054
bytes_read,
4055
bytes_to_fetch
4056
)
4057
m = self.assert_receive_message('LOG_DATA', timeout=2)
4058
self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4059
if m.ofs != bytes_read:
4060
raise NotAchievedException("Incorrect offset in reply want=%u got=%u (%s)" % (bytes_read, m.ofs, str(m)))
4061
stuff = m.data[0:m.count]
4062
data_downloaded.extend(stuff)
4063
bytes_read += m.count
4064
if len(data_downloaded) != bytes_read:
4065
raise NotAchievedException("extend fail")
4066
4067
if len(actual_bytes) != len(data_downloaded):
4068
raise NotAchievedException("Incorrect length: disk:%u downloaded: %u" %
4069
(len(actual_bytes), len(data_downloaded)))
4070
self.assert_bytes_equal(actual_bytes, data_downloaded)
4071
4072
self.start_subtest("Download log backwards")
4073
bytes_to_read = bytes_to_fetch
4074
if log_entry.size < bytes_to_read:
4075
bytes_to_read = log_entry.size
4076
bytes_read = 0
4077
backwards_data_downloaded = []
4078
last_print = 0
4079
while bytes_read < bytes_to_read:
4080
bytes_to_fetch = int(random.random() * 99) + 1
4081
if bytes_to_fetch > 90:
4082
bytes_to_fetch = 90
4083
if bytes_to_fetch > bytes_to_read - bytes_read:
4084
bytes_to_fetch = bytes_to_read - bytes_read
4085
ofs = bytes_to_read - bytes_read - bytes_to_fetch
4086
# self.progress("bytes_to_read=%u bytes_read=%u bytes_to_fetch=%u ofs=%d" %
4087
# (bytes_to_read, bytes_read, bytes_to_fetch, ofs))
4088
self.mav.mav.log_request_data_send(
4089
self.sysid_thismav(),
4090
1, # target component
4091
log_id,
4092
ofs,
4093
bytes_to_fetch
4094
)
4095
m = self.assert_receive_message('LOG_DATA', timeout=2)
4096
if m.count == 0:
4097
raise NotAchievedException("xZero bytes read (ofs=%u)" % (ofs,))
4098
if m.count > bytes_to_fetch:
4099
raise NotAchievedException("Read too many bytes?!")
4100
stuff = m.data[0:m.count]
4101
stuff.extend(backwards_data_downloaded)
4102
backwards_data_downloaded = stuff
4103
bytes_read += m.count
4104
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4105
if time.time() - last_print > 10:
4106
last_print = time.time()
4107
self.progress("xRead %u/%u" % (bytes_read, bytes_to_read))
4108
4109
self.assert_bytes_equal(actual_bytes, backwards_data_downloaded, maxlen=bytes_to_read)
4110
# if len(actual_bytes) != len(backwards_data_downloaded):
4111
# raise NotAchievedException("Size delta: actual=%u vs downloaded=%u" %
4112
# (len(actual_bytes), len(backwards_data_downloaded)))
4113
4114
def download_log(self, log_id, timeout=360):
4115
tstart = self.get_sim_time()
4116
data_downloaded = []
4117
bytes_read = 0
4118
last_print = 0
4119
while True:
4120
if self.get_sim_time_cached() - tstart > timeout:
4121
raise NotAchievedException("Did not download log in good time")
4122
self.mav.mav.log_request_data_send(
4123
self.sysid_thismav(),
4124
1, # target component
4125
log_id,
4126
bytes_read,
4127
90
4128
)
4129
m = self.assert_receive_message('LOG_DATA', timeout=2)
4130
if m.ofs != bytes_read:
4131
raise NotAchievedException(f"Unexpected offset {bytes_read=} {self.dump_message_verbose(m)}")
4132
if m.id != log_id:
4133
raise NotAchievedException(f"Unexpected id {log_id=} {self.dump_message_verbose(m)}")
4134
data_downloaded.extend(m.data[0:m.count])
4135
bytes_read += m.count
4136
if m.count < 90: # FIXME: constant
4137
break
4138
# self.progress("Read %u bytes at offset %u" % (m.count, m.ofs))
4139
if time.time() - last_print > 10:
4140
last_print = time.time()
4141
self.progress(f"{bytes_read=}")
4142
return data_downloaded
4143
4144
def TestLogDownloadLogRestart(self):
4145
'''test logging restarts after log download'''
4146
# self.delay_sim_time(30)
4147
self.set_parameters({
4148
"LOG_FILE_RATEMAX": 1,
4149
})
4150
self.reboot_sitl()
4151
number = self.current_onboard_log_number()
4152
content = self.download_log(number)
4153
print(f"Content is of length {len(content)}")
4154
# current_log_filepath = self.current_onboard_log_filepath()
4155
self.delay_sim_time(5)
4156
new_number = self.current_onboard_log_number()
4157
if number == new_number:
4158
raise NotAchievedException("Did not start logging again")
4159
new_content = self.download_log(new_number)
4160
if len(new_content) == 0:
4161
raise NotAchievedException(f"Unexpected length {len(new_content)=}")
4162
4163
#################################################
4164
# SIM UTILITIES
4165
#################################################
4166
def get_sim_time(self, timeout=60, drain_mav=True):
4167
"""Get SITL time in seconds."""
4168
if drain_mav:
4169
self.drain_mav()
4170
tstart = time.time()
4171
while True:
4172
self.drain_all_pexpects()
4173
if time.time() - tstart > timeout:
4174
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)
4175
4176
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=0.1)
4177
if m is None:
4178
continue
4179
4180
return m.time_boot_ms * 1.0e-3
4181
4182
def get_sim_time_cached(self):
4183
"""Get SITL time in seconds."""
4184
x = self.mav.messages.get("SYSTEM_TIME", None)
4185
if x is None:
4186
raise NotAchievedException("No cached time available (%s)" % (self.mav.sysid,))
4187
ret = x.time_boot_ms * 1.0e-3
4188
if ret != self.last_sim_time_cached:
4189
self.last_sim_time_cached = ret
4190
self.last_sim_time_cached_wallclock = time.time()
4191
else:
4192
timeout = 30
4193
if self.valgrind:
4194
timeout *= 10
4195
if time.time() - self.last_sim_time_cached_wallclock > timeout and not self.gdb:
4196
raise AutoTestTimeoutException("sim_time_cached is not updating!")
4197
return ret
4198
4199
def sim_location(self):
4200
"""Return current simulator location."""
4201
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
4202
return mavutil.location(m.lat*1.0e-7,
4203
m.lng*1.0e-7,
4204
0,
4205
math.degrees(m.yaw))
4206
4207
def sim_location_int(self):
4208
"""Return current simulator location."""
4209
m = self.mav.recv_match(type='SIMSTATE', blocking=True)
4210
return mavutil.location(m.lat,
4211
m.lng,
4212
0,
4213
math.degrees(m.yaw))
4214
4215
def save_wp(self, ch=7):
4216
"""Trigger RC Aux to save waypoint."""
4217
self.set_rc(ch, 1000)
4218
self.delay_sim_time(1)
4219
self.set_rc(ch, 2000)
4220
self.delay_sim_time(1)
4221
self.set_rc(ch, 1000)
4222
self.delay_sim_time(1)
4223
4224
def correct_wp_seq_numbers(self, wps):
4225
# renumber the items:
4226
count = 0
4227
for item in wps:
4228
item.seq = count
4229
count += 1
4230
4231
def create_simple_relhome_mission(self, 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
loc = self.home_relative_loc_ne(n, e)
4257
lat = loc.lat
4258
lng = loc.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
ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, x=int(lat*1e7), y=int(lng*1e7), z=alt))
4265
seq += 1
4266
4267
return ret
4268
4269
def upload_simple_relhome_mission(self, items, target_system=1, target_component=1):
4270
mission = self.create_simple_relhome_mission(
4271
items,
4272
target_system=target_system,
4273
target_component=target_component)
4274
self.check_mission_upload_download(mission)
4275
4276
def get_mission_count(self):
4277
return self.get_parameter("MIS_TOTAL")
4278
4279
def run_auxfunc(self,
4280
function,
4281
level,
4282
run_cmd=None,
4283
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
4284
if run_cmd is None:
4285
run_cmd = self.run_cmd
4286
run_cmd(
4287
mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION,
4288
p1=function,
4289
p2=level,
4290
want_result=want_result,
4291
)
4292
4293
def assert_mission_count(self, expected):
4294
count = self.get_mission_count()
4295
if count != expected:
4296
raise NotAchievedException("Unexpected count got=%u want=%u" %
4297
(count, expected))
4298
4299
def clear_wp(self, ch=8):
4300
"""Trigger RC Aux to clear waypoint."""
4301
self.progress("Clearing waypoints")
4302
self.set_rc(ch, 1000)
4303
self.delay_sim_time(0.5)
4304
self.set_rc(ch, 2000)
4305
self.delay_sim_time(0.5)
4306
self.set_rc(ch, 1000)
4307
self.assert_mission_count(0)
4308
4309
def log_list(self):
4310
'''return a list of log files present in POSIX-style loging dir'''
4311
ret = sorted(glob.glob("logs/00*.BIN"))
4312
self.progress("log list: %s" % str(ret))
4313
return ret
4314
4315
def assert_parameter_values(self, parameters, epsilon=None):
4316
names = parameters.keys()
4317
got = self.get_parameters(names)
4318
for name in names:
4319
equal = got[name] == parameters[name]
4320
if epsilon is not None:
4321
delta = abs(got[name] - parameters[name])
4322
equal = delta <= epsilon
4323
if not equal:
4324
raise NotAchievedException("parameter %s want=%f got=%f" %
4325
(name, parameters[name], got[name]))
4326
self.progress("%s has expected value %f" % (name, got[name]))
4327
4328
def assert_parameter_value(self, parameter, required, **kwargs):
4329
self.assert_parameter_values({
4330
parameter: required,
4331
}, **kwargs)
4332
4333
def assert_reach_imu_temperature(self, target, timeout):
4334
'''wait to reach a target temperature'''
4335
tstart = self.get_sim_time()
4336
temp_ok = False
4337
last_print_temp = -100
4338
while self.get_sim_time_cached() - tstart < timeout:
4339
m = self.assert_receive_message('RAW_IMU', timeout=2)
4340
temperature = m.temperature*0.01
4341
if temperature >= target:
4342
self.progress("Reached temperature %.1f" % temperature)
4343
temp_ok = True
4344
break
4345
if temperature - last_print_temp > 1:
4346
self.progress("temperature %.1f" % temperature)
4347
last_print_temp = temperature
4348
4349
if not temp_ok:
4350
raise NotAchievedException("target temperature")
4351
4352
def message_has_field_values_field_values_equal(self, fieldname, value, got, epsilon=None):
4353
if isinstance(value, float):
4354
if math.isnan(value) or math.isnan(got):
4355
return math.isnan(value) and math.isnan(got)
4356
4357
if type(value) is not str and epsilon is not None:
4358
return abs(got - value) <= epsilon
4359
4360
return got == value
4361
4362
def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
4363
for (fieldname, value) in fieldvalues.items():
4364
if "[" in fieldname: # fieldname == "arrayname[index]"
4365
assert fieldname[-1] == "]", fieldname
4366
arrayname, index = fieldname.split("[", 1)
4367
index = int(index[:-1])
4368
got = getattr(m, arrayname)[index]
4369
else:
4370
got = getattr(m, fieldname)
4371
4372
value_string = value
4373
got_string = got
4374
enum_name = m.fieldenums_by_name.get(fieldname, None)
4375
if enum_name is not None:
4376
enum = mavutil.mavlink.enums[enum_name]
4377
if value not in enum:
4378
raise ValueError("Expected value %s not in enum %s" % (value, enum_name))
4379
if got not in enum:
4380
raise ValueError("Received value %s not in enum %s" % (value, enum_name))
4381
value_string = "%s (%s)" % (value, enum[value].name)
4382
got_string = "%s (%s)" % (got, enum[got].name)
4383
4384
if not self.message_has_field_values_field_values_equal(
4385
fieldname, value, got, epsilon=epsilon
4386
):
4387
# see if this is an enumerated field:
4388
self.progress(self.dump_message_verbose(m))
4389
self.progress("Expected %s.%s to be %s, got %s" %
4390
(m.get_type(), fieldname, value_string, got_string))
4391
return False
4392
if verbose:
4393
self.progress("%s.%s has expected value %s" %
4394
(m.get_type(), fieldname, value_string))
4395
return True
4396
4397
def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
4398
if self.message_has_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon):
4399
return
4400
raise NotAchievedException("Did not get expected field values")
4401
4402
def assert_cached_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None):
4403
'''checks the most-recently received instance of message to ensure it
4404
has the correct field values'''
4405
m = self.get_cached_message(message)
4406
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
4407
return m
4408
4409
def assert_received_message_field_values(self,
4410
message,
4411
fieldvalues,
4412
verbose=True,
4413
very_verbose=False,
4414
epsilon=None,
4415
poll=False,
4416
timeout=None,
4417
check_context=False,
4418
):
4419
if poll:
4420
self.poll_message(message)
4421
m = self.assert_receive_message(
4422
message,
4423
verbose=verbose,
4424
very_verbose=very_verbose,
4425
timeout=timeout,
4426
check_context=check_context
4427
)
4428
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
4429
return m
4430
4431
# FIXME: try to use wait_and_maintain here?
4432
def wait_message_field_values(self,
4433
message,
4434
fieldvalues,
4435
timeout=10,
4436
epsilon=None,
4437
instance=None,
4438
minimum_duration=None,
4439
verbose=False,
4440
very_verbose=False,
4441
):
4442
4443
tstart = self.get_sim_time_cached()
4444
pass_start = None
4445
last_debug = 0
4446
while True:
4447
now = self.get_sim_time_cached()
4448
if now - tstart > timeout:
4449
raise NotAchievedException("Field never reached values")
4450
m = self.assert_receive_message(
4451
message,
4452
instance=instance,
4453
verbose=verbose,
4454
very_verbose=very_verbose,
4455
)
4456
if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose):
4457
if minimum_duration is not None:
4458
if pass_start is None:
4459
pass_start = now
4460
continue
4461
delta = now - pass_start
4462
if now - last_debug >= 1:
4463
last_debug = now
4464
self.progress(f"Good field values ({delta:.2f}s/{minimum_duration}s)")
4465
if delta < minimum_duration:
4466
continue
4467
else:
4468
self.progress("Reached field values")
4469
return m
4470
pass_start = None
4471
4472
def onboard_logging_not_log_disarmed(self):
4473
self.start_subtest("Test LOG_DISARMED-is-false behaviour")
4474
self.set_parameter("LOG_DISARMED", 0)
4475
self.set_parameter("LOG_FILE_DSRMROT", 0)
4476
self.reboot_sitl()
4477
self.wait_ready_to_arm() # let things setttle
4478
self.start_subtest("Ensure setting LOG_DISARMED yields a new file")
4479
original_list = self.log_list()
4480
self.progress("original list: %s" % str(original_list))
4481
self.set_parameter("LOG_DISARMED", 1)
4482
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4483
new_list = self.log_list()
4484
self.progress("new list: %s" % str(new_list))
4485
if len(new_list) - len(original_list) != 1:
4486
raise NotAchievedException("Got more than one new log")
4487
self.set_parameter("LOG_DISARMED", 0)
4488
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4489
new_list = self.log_list()
4490
if len(new_list) - len(original_list) != 1:
4491
raise NotAchievedException("Got more or less than one new log after toggling LOG_DISARMED off")
4492
4493
self.start_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")
4494
self.set_parameter("LOG_DISARMED", 1)
4495
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4496
new_new_list = self.log_list()
4497
if len(new_new_list) != len(new_list):
4498
raise NotAchievedException("Got extra files when toggling LOG_DISARMED")
4499
self.set_parameter("LOG_DISARMED", 0)
4500
self.delay_sim_time(1) # LOG_DISARMED is polled by the logger code
4501
new_new_list = self.log_list()
4502
if len(new_new_list) != len(new_list):
4503
raise NotAchievedException("Got extra files when toggling LOG_DISARMED to 0 again")
4504
self.end_subtest("Ensuring toggling LOG_DISARMED on and off doesn't increase the number of files")
4505
4506
self.start_subtest("Check disarm rot when log disarmed is zero")
4507
self.assert_parameter_value("LOG_DISARMED", 0)
4508
self.set_parameter("LOG_FILE_DSRMROT", 1)
4509
old_speedup = self.get_parameter("SIM_SPEEDUP")
4510
# reduce speedup to reduce chance of race condition here
4511
self.set_parameter("SIM_SPEEDUP", 1)
4512
pre_armed_list = self.log_list()
4513
if self.is_copter() or self.is_heli():
4514
self.set_parameter("DISARM_DELAY", 0)
4515
self.arm_vehicle()
4516
post_armed_list = self.log_list()
4517
if len(post_armed_list) != len(pre_armed_list):
4518
raise NotAchievedException("Got unexpected new log")
4519
self.disarm_vehicle()
4520
old_speedup = self.set_parameter("SIM_SPEEDUP", old_speedup)
4521
post_disarmed_list = self.log_list()
4522
if len(post_disarmed_list) != len(post_armed_list):
4523
raise NotAchievedException("Log rotated immediately")
4524
self.progress("Allowing time for post-disarm-logging to occur if it will")
4525
self.delay_sim_time(5)
4526
post_disarmed_post_delay_list = self.log_list()
4527
if len(post_disarmed_post_delay_list) != len(post_disarmed_list):
4528
raise NotAchievedException("Got log rotation when we shouldn't have")
4529
self.progress("Checking that arming does produce a new log")
4530
self.arm_vehicle()
4531
post_armed_list = self.log_list()
4532
if len(post_armed_list) - len(post_disarmed_post_delay_list) != 1:
4533
raise NotAchievedException("Did not get new log for rotation")
4534
self.progress("Now checking natural rotation after HAL_LOGGER_ARM_PERSIST")
4535
self.disarm_vehicle()
4536
post_disarmed_list = self.log_list()
4537
if len(post_disarmed_list) != len(post_armed_list):
4538
raise NotAchievedException("Log rotated immediately")
4539
self.delay_sim_time(30)
4540
delayed_post_disarmed_list = self.log_list()
4541
# should *still* not get another log as LOG_DISARMED is false
4542
if len(post_disarmed_list) != len(delayed_post_disarmed_list):
4543
self.progress("Unexpected new log found")
4544
4545
def onboard_logging_log_disarmed(self):
4546
self.start_subtest("Test LOG_DISARMED-is-true behaviour")
4547
start_list = self.log_list()
4548
self.set_parameter("LOG_FILE_DSRMROT", 0)
4549
self.set_parameter("LOG_DISARMED", 0)
4550
self.reboot_sitl()
4551
restart_list = self.log_list()
4552
if len(start_list) != len(restart_list):
4553
raise NotAchievedException(
4554
"Unexpected log detected (pre-delay) initial=(%s) restart=(%s)" %
4555
(str(sorted(start_list)), str(sorted(restart_list))))
4556
self.delay_sim_time(20)
4557
restart_list = self.log_list()
4558
if len(start_list) != len(restart_list):
4559
raise NotAchievedException("Unexpected log detected (post-delay)")
4560
self.set_parameter("LOG_DISARMED", 1)
4561
self.delay_sim_time(5) # LOG_DISARMED is polled
4562
post_log_disarmed_set_list = self.log_list()
4563
if len(post_log_disarmed_set_list) == len(restart_list):
4564
raise NotAchievedException("Did not get new log when LOG_DISARMED set")
4565
self.progress("Ensuring we get a new log after a reboot")
4566
self.reboot_sitl()
4567
self.delay_sim_time(5)
4568
post_reboot_log_list = self.log_list()
4569
if len(post_reboot_log_list) == len(post_log_disarmed_set_list):
4570
raise NotAchievedException("Did not get fresh log-disarmed log after a reboot")
4571
self.progress("Ensuring no log rotation when we toggle LOG_DISARMED off then on again")
4572
self.set_parameter("LOG_DISARMED", 0)
4573
current_log_filepath = self.current_onboard_log_filepath()
4574
self.delay_sim_time(10) # LOG_DISARMED is polled
4575
post_toggleoff_list = self.log_list()
4576
if len(post_toggleoff_list) != len(post_reboot_log_list):
4577
raise NotAchievedException("Shouldn't get new file yet")
4578
self.progress("Ensuring log does not grow when LOG_DISARMED unset...")
4579
current_log_filepath_size = os.path.getsize(current_log_filepath)
4580
self.delay_sim_time(5)
4581
current_log_filepath_new_size = os.path.getsize(current_log_filepath)
4582
if current_log_filepath_new_size != current_log_filepath_size:
4583
raise NotAchievedException(
4584
"File growing after LOG_DISARMED unset (new=%u old=%u" %
4585
(current_log_filepath_new_size, current_log_filepath_size))
4586
self.progress("Turning LOG_DISARMED back on again")
4587
self.set_parameter("LOG_DISARMED", 1)
4588
self.delay_sim_time(5) # LOG_DISARMED is polled
4589
post_toggleon_list = self.log_list()
4590
if len(post_toggleon_list) != len(post_toggleoff_list):
4591
raise NotAchievedException("Log rotated when it shouldn't")
4592
self.progress("Checking log is now growing again")
4593
if os.path.getsize(current_log_filepath) == current_log_filepath_size:
4594
raise NotAchievedException("Log is not growing")
4595
4596
# self.progress("Checking LOG_FILE_DSRMROT behaviour when log_DISARMED set")
4597
# self.set_parameter("LOG_FILE_DSRMROT", 1)
4598
# self.wait_ready_to_arm()
4599
# pre = self.log_list()
4600
# self.arm_vehicle()
4601
# post = self.log_list()
4602
# if len(pre) != len(post):
4603
# raise NotAchievedException("Rotation happened on arming?!")
4604
# size_a = os.path.getsize(current_log_filepath)
4605
# self.delay_sim_time(5)
4606
# size_b = os.path.getsize(current_log_filepath)
4607
# if size_b <= size_a:
4608
# raise NotAchievedException("Log not growing")
4609
# self.disarm_vehicle()
4610
# instant_post_disarm_list = self.log_list()
4611
# self.progress("Should not rotate straight away")
4612
# if len(instant_post_disarm_list) != len(post):
4613
# raise NotAchievedException("Should not rotate straight away")
4614
# self.delay_sim_time(20)
4615
# post_disarm_list = self.log_list()
4616
# if len(post_disarm_list) - len(instant_post_disarm_list) != 1:
4617
# raise NotAchievedException("Did not get exactly one more log")
4618
4619
# self.progress("If we re-arm during the HAL_LOGGER_ARM_PERSIST period it should rotate")
4620
4621
def onboard_logging_forced_arm(self):
4622
'''ensure a bug where we didn't start logging when arming was forced
4623
does not reappear'''
4624
self.start_subtest("Ensure we get a log when force-arming")
4625
self.set_parameter("LOG_DISARMED", 0)
4626
self.reboot_sitl() # so we'll definitely start a log on arming
4627
pre_arming_list = self.log_list()
4628
self.wait_ready_to_arm()
4629
self.arm_vehicle(force=True)
4630
# we might be relying on a thread to actually create the log
4631
# file when doing forced-arming; give the file time to appear:
4632
self.delay_sim_time(10)
4633
post_arming_list = self.log_list()
4634
self.disarm_vehicle()
4635
if len(post_arming_list) <= len(pre_arming_list):
4636
raise NotAchievedException("Did not get a log on forced arm")
4637
4638
def Logging(self):
4639
'''Test Onboard Logging'''
4640
if self.is_tracker():
4641
return
4642
self.onboard_logging_forced_arm()
4643
self.onboard_logging_log_disarmed()
4644
self.onboard_logging_not_log_disarmed()
4645
4646
def LoggingFormatSanityChecks(self, path):
4647
dfreader = self.dfreader_for_path(path)
4648
first_message = dfreader.recv_match()
4649
if first_message.get_type() != 'FMT':
4650
raise NotAchievedException("Expected first message to be a FMT message")
4651
if first_message.Name != 'FMT':
4652
raise NotAchievedException("Expected first message to be the FMT FMT message")
4653
4654
self.progress("Ensuring DCM format is received") # it's a WriteStreaming message...
4655
while True:
4656
m = dfreader.recv_match(type='FMT')
4657
if m is None:
4658
raise NotAchievedException("Did not find DCM format")
4659
if m.Name != 'DCM':
4660
continue
4661
self.progress("Found DCM format")
4662
break
4663
4664
self.progress("No message should appear before its format")
4665
dfreader.rewind()
4666
seen_formats = set()
4667
while True:
4668
m = dfreader.recv_match()
4669
if m is None:
4670
break
4671
m_type = m.get_type()
4672
if m_type == 'FMT':
4673
seen_formats.add(m.Name)
4674
continue
4675
if m_type not in seen_formats:
4676
raise ValueError(f"{m_type} seen before its format")
4677
# print(f"{m_type} OK")
4678
4679
def LoggingFormat(self):
4680
'''ensure formats are emmitted appropriately'''
4681
4682
self.context_push()
4683
self.set_parameter('LOG_FILE_DSRMROT', 1)
4684
self.wait_ready_to_arm()
4685
for i in range(3):
4686
self.arm_vehicle()
4687
self.delay_sim_time(5)
4688
path = self.current_onboard_log_filepath()
4689
self.disarm_vehicle()
4690
self.LoggingFormatSanityChecks(path)
4691
self.context_pop()
4692
4693
self.context_push()
4694
for i in range(3):
4695
self.set_parameter("LOG_DISARMED", 1)
4696
self.reboot_sitl()
4697
self.delay_sim_time(5)
4698
path = self.current_onboard_log_filepath()
4699
self.set_parameter("LOG_DISARMED", 0)
4700
self.LoggingFormatSanityChecks(path)
4701
self.context_pop()
4702
4703
def TestLogDownloadMAVProxy(self, upload_logs=False):
4704
"""Download latest log."""
4705
filename = "MAVProxy-downloaded-log.BIN"
4706
mavproxy = self.start_mavproxy()
4707
self.mavproxy_load_module(mavproxy, 'log')
4708
self.set_parameter('SIM_SPEEDUP', 1)
4709
mavproxy.send("log list\n")
4710
mavproxy.expect("numLogs")
4711
self.wait_heartbeat()
4712
self.wait_heartbeat()
4713
mavproxy.send("set shownoise 0\n")
4714
mavproxy.send("log download latest %s\n" % filename)
4715
mavproxy.expect("Finished downloading", timeout=120)
4716
self.mavproxy_unload_module(mavproxy, 'log')
4717
self.stop_mavproxy(mavproxy)
4718
4719
def TestLogDownloadMAVProxyNetwork(self, upload_logs=False):
4720
"""Download latest log over network port"""
4721
self.context_push()
4722
self.set_parameters({
4723
"NET_ENABLE": 1,
4724
"LOG_DISARMED": 0,
4725
"LOG_DARM_RATEMAX": 1, # make small logs
4726
# UDP client
4727
"NET_P1_TYPE": 1,
4728
"NET_P1_PROTOCOL": 2,
4729
"NET_P1_PORT": 16001,
4730
"NET_P1_IP0": 127,
4731
"NET_P1_IP1": 0,
4732
"NET_P1_IP2": 0,
4733
"NET_P1_IP3": 1,
4734
# UDP server
4735
"NET_P2_TYPE": 2,
4736
"NET_P2_PROTOCOL": 2,
4737
"NET_P2_PORT": 16002,
4738
"NET_P2_IP0": 0,
4739
"NET_P2_IP1": 0,
4740
"NET_P2_IP2": 0,
4741
"NET_P2_IP3": 0,
4742
# TCP client
4743
"NET_P3_TYPE": 3,
4744
"NET_P3_PROTOCOL": 2,
4745
"NET_P3_PORT": 16003,
4746
"NET_P3_IP0": 127,
4747
"NET_P3_IP1": 0,
4748
"NET_P3_IP2": 0,
4749
"NET_P3_IP3": 1,
4750
# TCP server
4751
"NET_P4_TYPE": 4,
4752
"NET_P4_PROTOCOL": 2,
4753
"NET_P4_PORT": 16004,
4754
"NET_P4_IP0": 0,
4755
"NET_P4_IP1": 0,
4756
"NET_P4_IP2": 0,
4757
"NET_P4_IP3": 0,
4758
})
4759
self.reboot_sitl()
4760
4761
# ensure the latest log file is very small:
4762
self.context_push()
4763
self.set_parameter('LOG_DISARMED', 1)
4764
self.delay_sim_time(15)
4765
self.progress(f"Current onboard log filepath {self.current_onboard_log_filepath()}")
4766
self.context_pop()
4767
4768
# ensure that the autopilot has a timestamp on that file by
4769
# now, or MAVProxy does not see it as the latest log:
4770
self.wait_gps_fix_type_gte(3)
4771
4772
self.set_parameter('SIM_SPEEDUP', 1)
4773
4774
endpoints = [('UDPClient', ':16001') ,
4775
('UDPServer', 'udpout:127.0.0.1:16002'),
4776
('TCPClient', 'tcpin:0.0.0.0:16003'),
4777
('TCPServer', 'tcp:127.0.0.1:16004')]
4778
for name, e in endpoints:
4779
self.progress("Downloading log with %s %s" % (name, e))
4780
filename = "MAVProxy-downloaded-net-log-%s.BIN" % name
4781
4782
mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])
4783
self.mavproxy_load_module(mavproxy, 'log')
4784
self.wait_heartbeat()
4785
mavproxy.send("log list\n")
4786
mavproxy.expect("numLogs")
4787
# ensure the full list of logs has come out
4788
for i in range(5):
4789
self.wait_heartbeat()
4790
mavproxy.send("log download latest %s\n" % filename)
4791
mavproxy.expect("Finished downloading", timeout=120)
4792
self.mavproxy_unload_module(mavproxy, 'log')
4793
self.stop_mavproxy(mavproxy)
4794
4795
self.set_parameters({
4796
# multicast UDP client
4797
"NET_P1_TYPE": 1,
4798
"NET_P1_PROTOCOL": 2,
4799
"NET_P1_PORT": 16005,
4800
"NET_P1_IP0": 239,
4801
"NET_P1_IP1": 255,
4802
"NET_P1_IP2": 145,
4803
"NET_P1_IP3": 50,
4804
# Broadcast UDP client
4805
"NET_P2_TYPE": 1,
4806
"NET_P2_PROTOCOL": 2,
4807
"NET_P2_PORT": 16006,
4808
"NET_P2_IP0": 255,
4809
"NET_P2_IP1": 255,
4810
"NET_P2_IP2": 255,
4811
"NET_P2_IP3": 255,
4812
"NET_P3_TYPE": -1,
4813
"NET_P4_TYPE": -1,
4814
"LOG_DISARMED": 0,
4815
})
4816
self.reboot_sitl()
4817
4818
self.set_parameter('SIM_SPEEDUP', 1)
4819
4820
endpoints = [('UDPMulticast', 'mcast:16005') ,
4821
('UDPBroadcast', ':16006')]
4822
for name, e in endpoints:
4823
self.progress("Downloading log with %s %s" % (name, e))
4824
filename = "MAVProxy-downloaded-net-log-%s.BIN" % name
4825
4826
mavproxy = self.start_mavproxy(master=e, options=['--source-system=123'])
4827
self.mavproxy_load_module(mavproxy, 'log')
4828
self.wait_heartbeat()
4829
mavproxy.send("log list\n")
4830
mavproxy.expect("numLogs")
4831
# ensure the full list of logs has come out
4832
for i in range(5):
4833
self.wait_heartbeat()
4834
mavproxy.send("log download latest %s\n" % filename)
4835
mavproxy.expect("Finished downloading", timeout=120)
4836
self.mavproxy_unload_module(mavproxy, 'log')
4837
self.stop_mavproxy(mavproxy)
4838
4839
self.context_pop()
4840
4841
def TestLogDownloadMAVProxyCAN(self, upload_logs=False):
4842
"""Download latest log over CAN serial port"""
4843
self.context_push()
4844
self.set_parameters({
4845
"CAN_P1_DRIVER": 1,
4846
"LOG_DISARMED": 1,
4847
})
4848
self.reboot_sitl()
4849
self.set_parameters({
4850
"CAN_D1_UC_SER_EN": 1,
4851
"CAN_D1_UC_S1_NOD": 125,
4852
"CAN_D1_UC_S1_IDX": 4,
4853
"CAN_D1_UC_S1_BD": 57600,
4854
"CAN_D1_UC_S1_PRO": 2,
4855
})
4856
self.reboot_sitl()
4857
4858
self.set_parameter('SIM_SPEEDUP', 1)
4859
4860
filename = "MAVProxy-downloaded-can-log.BIN"
4861
# port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:15550
4862
mavproxy = self.start_mavproxy(master=':15550')
4863
mavproxy.expect("Detected vehicle")
4864
self.mavproxy_load_module(mavproxy, 'log')
4865
mavproxy.send("log list\n")
4866
mavproxy.expect("numLogs")
4867
# ensure the full list of logs has come out
4868
for i in range(5):
4869
self.wait_heartbeat()
4870
mavproxy.send("set shownoise 0\n")
4871
mavproxy.send("log download latest %s\n" % filename)
4872
mavproxy.expect("Finished downloading", timeout=120)
4873
self.mavproxy_unload_module(mavproxy, 'log')
4874
self.stop_mavproxy(mavproxy)
4875
self.context_pop()
4876
4877
def show_gps_and_sim_positions(self, on_off):
4878
"""Allow to display gps and actual position on map."""
4879
if on_off is True:
4880
# turn on simulator display of gps and actual position
4881
self.mavproxy.send('map set showgpspos 1\n')
4882
self.mavproxy.send('map set showsimpos 1\n')
4883
else:
4884
# turn off simulator display of gps and actual position
4885
self.mavproxy.send('map set showgpspos 0\n')
4886
self.mavproxy.send('map set showsimpos 0\n')
4887
4888
@staticmethod
4889
def mission_count(filename):
4890
"""Load a mission from a file and return number of waypoints."""
4891
wploader = mavwp.MAVWPLoader()
4892
wploader.load(filename)
4893
return wploader.count()
4894
4895
def install_message_hook(self, hook):
4896
self.message_hooks.append(hook)
4897
4898
def install_message_hook_context(self, hook):
4899
'''installs a message hook which will be removed when the context goes
4900
away'''
4901
if self.mav is None:
4902
return
4903
self.message_hooks.append(hook)
4904
self.context_get().message_hooks.append(hook)
4905
4906
def remove_message_hook(self, hook):
4907
'''remove hook from list of message hooks. Assumes it exists exactly
4908
once'''
4909
if self.mav is None:
4910
return
4911
self.message_hooks.remove(hook)
4912
if isinstance(hook, TestSuite.MessageHook):
4913
hook.hook_removed()
4914
4915
def install_example_script_context(self, scriptname):
4916
'''installs an example script which will be removed when the context goes
4917
away'''
4918
self.install_example_script(scriptname)
4919
self.context_get().installed_scripts.append(scriptname)
4920
4921
def install_test_script_context(self, scriptnames):
4922
'''installs an test script which will be removed when the context goes
4923
away'''
4924
if isinstance(scriptnames, str):
4925
scriptnames = [scriptnames]
4926
for scriptname in scriptnames:
4927
self.install_test_script(scriptname)
4928
self.context_get().installed_scripts.extend(scriptnames)
4929
4930
def install_test_scripts_context(self, *args, **kwargs):
4931
'''same as install_test_scripts_context - just pluralised name'''
4932
return self.install_test_script_context(*args, **kwargs)
4933
4934
def install_test_modules_context(self):
4935
'''installs test modules which will be removed when the context goes
4936
away'''
4937
self.install_test_modules()
4938
self.context_get().installed_modules.append("test")
4939
4940
def install_mavlink_module_context(self):
4941
'''installs mavlink module which will be removed when the context goes
4942
away'''
4943
self.install_mavlink_module()
4944
self.context_get().installed_modules.append("mavlink")
4945
4946
def install_applet_script_context(self, scriptname, **kwargs):
4947
'''installs an applet script which will be removed when the context goes
4948
away'''
4949
self.install_applet_script(scriptname, **kwargs)
4950
self.context_get().installed_scripts.append(scriptname)
4951
4952
def rootdir(self):
4953
this_dir = os.path.dirname(__file__)
4954
return os.path.realpath(os.path.join(this_dir, "../.."))
4955
4956
def ardupilot_stores_frame_for_cmd(self, t):
4957
# ardupilot doesn't remember frame on these commands
4958
return t not in [
4959
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
4960
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
4961
mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
4962
mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,
4963
mavutil.mavlink.MAV_CMD_DO_JUMP,
4964
mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
4965
mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
4966
mavutil.mavlink.MAV_CMD_DO_SET_SERVO,
4967
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
4968
]
4969
4970
def assert_mission_files_same(self, file1, file2, match_comments=False):
4971
self.progress("Comparing (%s) and (%s)" % (file1, file2, ))
4972
4973
f1 = open(file1)
4974
f2 = open(file2)
4975
lines1 = f1.readlines()
4976
lines2 = f2.readlines()
4977
4978
if not match_comments:
4979
# strip comments from all lines
4980
lines1 = [re.sub(r"\s*#.*", "", x, re.DOTALL) for x in lines1]
4981
lines2 = [re.sub(r"\s*#.*", "", x, re.DOTALL) for x in lines2]
4982
# FIXME: because DOTALL doesn't seem to work as expected:
4983
lines1 = [x.rstrip() for x in lines1]
4984
lines2 = [x.rstrip() for x in lines2]
4985
# remove now-empty lines:
4986
lines1 = filter(lambda x: len(x), lines1)
4987
lines2 = filter(lambda x: len(x), lines2)
4988
4989
for l1, l2 in zip(lines1, lines2):
4990
l1 = l1.rstrip("\r\n")
4991
l2 = l2.rstrip("\r\n")
4992
if l1 == l2:
4993
# e.g. the first "QGC WPL 110" line
4994
continue
4995
if re.match(r"0\s", l1):
4996
# home changes...
4997
continue
4998
l1 = l1.rstrip()
4999
l2 = l2.rstrip()
5000
fields1 = re.split(r"\s+", l1)
5001
fields2 = re.split(r"\s+", l2)
5002
# line = int(fields1[0])
5003
t = int(fields1[3]) # mission item type
5004
for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):
5005
if count == 2: # frame
5006
if not self.ardupilot_stores_frame_for_cmd(t):
5007
if int(i1) in [3, 10]: # 3 is relative, 10 is terrain
5008
i1 = 0
5009
if int(i2) in [3, 10]:
5010
i2 = 0
5011
if count == 6: # param 3
5012
if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:
5013
# ardupilot canonicalises this to -1 for ccw or 1 for cw.
5014
if float(i1) == 0:
5015
i1 = 1.0
5016
if float(i2) == 0:
5017
i2 = 1.0
5018
if count == 7: # param 4
5019
if t == mavutil.mavlink.MAV_CMD_NAV_LAND:
5020
# ardupilot canonicalises "0" to "1" param 4 (yaw)
5021
if int(float(i1)) == 0:
5022
i1 = 1
5023
if int(float(i2)) == 0:
5024
i2 = 1
5025
if 0 <= count <= 3 or 11 <= count <= 11:
5026
if int(i1) != int(i2):
5027
raise ValueError("Files have different content: (%s vs %s) (%s vs %s) (%d vs %d) (count=%u)" %
5028
(file1, file2, l1, l2, int(i1), int(i2), count)) # NOCI
5029
continue
5030
if 4 <= count <= 10:
5031
f_i1 = float(i1)
5032
f_i2 = float(i2)
5033
delta = abs(f_i1 - f_i2)
5034
max_allowed_delta = 0.000009
5035
if delta > max_allowed_delta:
5036
raise ValueError(
5037
("Files have different (float) content: " +
5038
"(%s) and (%s) " +
5039
"(%s vs %s) " +
5040
"(%f vs %f) " +
5041
"(%.10f) " +
5042
"(count=%u)") %
5043
(file1, file2,
5044
l1, l2,
5045
f_i1, f_i2,
5046
delta,
5047
count)) # NOCI
5048
continue
5049
raise ValueError("count %u not handled" % count)
5050
self.progress("Files same")
5051
5052
def assert_not_receive_message(self, message, timeout=1, mav=None, condition=None):
5053
'''this is like assert_not_receiving_message but uses sim time not
5054
wallclock time'''
5055
self.progress("making sure we're not getting %s messages" % message)
5056
if mav is None:
5057
mav = self.mav
5058
5059
tstart = self.get_sim_time_cached()
5060
while True:
5061
m = mav.recv_match(type=message, blocking=True, timeout=0.1, condition=condition)
5062
if m is not None:
5063
self.progress("Received: %s" % self.dump_message_verbose(m))
5064
raise PreconditionFailedException("Receiving %s messages" % message)
5065
if mav != self.mav:
5066
# update timestamp....
5067
self.drain_mav(self.mav)
5068
if self.get_sim_time_cached() - tstart > timeout:
5069
return
5070
5071
def assert_receive_message(self,
5072
type,
5073
timeout=None,
5074
verbose=False,
5075
very_verbose=False,
5076
mav=None,
5077
condition=None,
5078
delay_fn=None,
5079
instance=None,
5080
check_context=False):
5081
if timeout is None:
5082
timeout = 1
5083
if mav is None:
5084
mav = self.mav
5085
5086
if check_context:
5087
collection = self.context_collection(type)
5088
if len(collection) > 0:
5089
# return the most-recently-received message:
5090
return collection[-1]
5091
5092
m = None
5093
tstart = time.time() # timeout in wallclock
5094
while True:
5095
m = mav.recv_match(type=type, blocking=True, timeout=0.05, condition=condition)
5096
if instance is not None:
5097
if getattr(m, m._instance_field) != instance:
5098
continue
5099
if m is not None:
5100
break
5101
elapsed_time = time.time() - tstart
5102
if elapsed_time > timeout:
5103
raise NotAchievedException("Did not get %s after %s seconds" %
5104
(type, elapsed_time))
5105
if delay_fn is not None:
5106
delay_fn()
5107
if verbose:
5108
self.progress("Received (%s)" % str(m))
5109
if very_verbose:
5110
self.progress(self.dump_message_verbose(m))
5111
return m
5112
5113
def assert_receive_named_value_float(self, name, timeout=10):
5114
tstart = self.get_sim_time_cached()
5115
while True:
5116
if self.get_sim_time_cached() - tstart > timeout:
5117
raise NotAchievedException("Did not get NAMED_VALUE_FLOAT %s" % name)
5118
m = self.assert_receive_message('NAMED_VALUE_FLOAT', verbose=1, very_verbose=1, timeout=timeout)
5119
if m.name != name:
5120
continue
5121
return m
5122
5123
def assert_receive_named_value_float_value(self, name, value, epsilon=0.0001, timeout=10):
5124
m = self.assert_receive_named_value_float_value(name, timeout=timeout)
5125
if abs(m.value - value) > epsilon:
5126
raise NotAchievedException("Bad %s want=%f got=%f" % (name, value, m.value))
5127
5128
def assert_rally_files_same(self, file1, file2):
5129
self.progress("Comparing (%s) and (%s)" % (file1, file2, ))
5130
f1 = open(file1)
5131
f2 = open(file2)
5132
lines_f1 = f1.readlines()
5133
lines_f2 = f2.readlines()
5134
self.assert_rally_content_same(lines_f1, lines_f2)
5135
5136
def assert_rally_filepath_content(self, file1, content):
5137
f1 = open(file1)
5138
lines_f1 = f1.readlines()
5139
lines_content = content.split("\n")
5140
print("lines content: %s" % str(lines_content))
5141
self.assert_rally_content_same(lines_f1, lines_content)
5142
5143
def assert_rally_content_same(self, f1, f2):
5144
'''check each line in f1 matches one-to-one with f2'''
5145
for l1, l2 in zip(f1, f2):
5146
print("l1: %s" % l1)
5147
print("l2: %s" % l2)
5148
l1 = l1.rstrip("\n")
5149
l2 = l2.rstrip("\n")
5150
l1 = l1.rstrip("\r")
5151
l2 = l2.rstrip("\r")
5152
if l1 == l2:
5153
# e.g. the first "QGC WPL 110" line
5154
continue
5155
if re.match(r"0\s", l1):
5156
# home changes...
5157
continue
5158
l1 = l1.rstrip()
5159
l2 = l2.rstrip()
5160
print("al1: %s" % str(l1))
5161
print("al2: %s" % str(l2))
5162
fields1 = re.split(r"\s+", l1)
5163
fields2 = re.split(r"\s+", l2)
5164
# line = int(fields1[0])
5165
# t = int(fields1[3]) # mission item type
5166
for (count, (i1, i2)) in enumerate(zip(fields1, fields2)):
5167
# if count == 2: # frame
5168
# if t in [mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED,
5169
# mavutil.mavlink.MAV_CMD_CONDITION_YAW,
5170
# mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH,
5171
# mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME,
5172
# mavutil.mavlink.MAV_CMD_DO_JUMP,
5173
# mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
5174
# ]:
5175
# # ardupilot doesn't remember frame on these commands
5176
# if int(i1) == 3:
5177
# i1 = 0
5178
# if int(i2) == 3:
5179
# i2 = 0
5180
# if count == 6: # param 3
5181
# if t in [mavutil.mavlink.MAV_CMD_NAV_LOITER_TIME]:
5182
# # ardupilot canonicalises this to -1 for ccw or 1 for cw.
5183
# if float(i1) == 0:
5184
# i1 = 1.0
5185
# if float(i2) == 0:
5186
# i2 = 1.0
5187
# if count == 7: # param 4
5188
# if t == mavutil.mavlink.MAV_CMD_NAV_LAND:
5189
# # ardupilot canonicalises "0" to "1" param 4 (yaw)
5190
# if int(float(i1)) == 0:
5191
# i1 = 1
5192
# if int(float(i2)) == 0:
5193
# i2 = 1
5194
if 0 <= count <= 3 or 11 <= count <= 11:
5195
if int(i1) != int(i2):
5196
raise ValueError("Rally points different: (%s vs %s) (%d vs %d) (count=%u)" %
5197
(l1, l2, int(i1), int(i2), count)) # NOCI
5198
continue
5199
if 4 <= count <= 10:
5200
f_i1 = float(i1)
5201
f_i2 = float(i2)
5202
delta = abs(f_i1 - f_i2)
5203
max_allowed_delta = 0.000009
5204
if delta > max_allowed_delta:
5205
raise ValueError(
5206
("Rally has different (float) content: " +
5207
"(%s vs %s) " +
5208
"(%f vs %f) " +
5209
"(%.10f) " +
5210
"(count=%u)") %
5211
(l1, l2,
5212
f_i1, f_i2,
5213
delta,
5214
count)) # NOCI
5215
continue
5216
raise ValueError("count %u not handled" % count)
5217
self.progress("Rally content same")
5218
5219
def load_rally_using_mavproxy(self, filename):
5220
"""Load rally points from a file to flight controller."""
5221
self.progress("Loading rally points (%s)" % filename)
5222
path = os.path.join(testdir, self.current_test_name_directory, filename)
5223
mavproxy = self.start_mavproxy()
5224
mavproxy.send('rally load %s\n' % path)
5225
mavproxy.expect("Loaded")
5226
self.delay_sim_time(10) # allow transfer to complete
5227
self.stop_mavproxy(mavproxy)
5228
5229
def load_sample_mission(self):
5230
self.load_mission(self.sample_mission_filename())
5231
5232
def generic_mission_filepath_for_filename(self, filename):
5233
return os.path.join(testdir, "Generic_Missions", filename)
5234
5235
def load_generic_mission(self, filename, strict=True):
5236
return self.load_mission_from_filepath(
5237
self.generic_mission_filepath_for_filename(filename),
5238
strict=strict)
5239
5240
def load_mission(self, filename, strict=True):
5241
return self.load_mission_from_filepath(
5242
os.path.join(testdir, self.current_test_name_directory, filename),
5243
strict=strict)
5244
5245
def wp_to_mission_item_int(self, wp, mission_type):
5246
'''convert a MISSION_ITEM to a MISSION_ITEM_INT. We always send as
5247
MISSION_ITEM_INT to give cm level accuracy
5248
Swiped from mavproxy_wp.py
5249
'''
5250
if wp.get_type() == 'MISSION_ITEM_INT':
5251
return wp
5252
wp_int = mavutil.mavlink.MAVLink_mission_item_int_message(
5253
wp.target_system,
5254
wp.target_component,
5255
wp.seq,
5256
wp.frame,
5257
wp.command,
5258
wp.current,
5259
wp.autocontinue,
5260
wp.param1,
5261
wp.param2,
5262
wp.param3,
5263
wp.param4,
5264
int(wp.x*1.0e7),
5265
int(wp.y*1.0e7),
5266
wp.z,
5267
mission_type,
5268
)
5269
return wp_int
5270
5271
def mission_item_protocol_items_from_filepath(self,
5272
loaderclass,
5273
filepath,
5274
target_system=1,
5275
target_component=1,
5276
):
5277
'''returns a list of mission-item-ints from filepath'''
5278
# self.progress("filepath: %s" % filepath)
5279
wploader = loaderclass(
5280
target_system=target_system,
5281
target_component=target_component
5282
)
5283
itemstype = mavutil.mavlink.enums["MAV_MISSION_TYPE"][wploader.mav_mission_type()]
5284
self.progress(f"Loading {itemstype} ({os.path.basename(filepath)}")
5285
wploader.load(filepath)
5286
return [self.wp_to_mission_item_int(x, wploader.mav_mission_type()) for x in wploader.wpoints] # noqa:502
5287
5288
def mission_from_filepath(self, filepath, target_system=1, target_component=1):
5289
'''returns a list of mission-item-ints from filepath'''
5290
return self.mission_item_protocol_items_from_filepath(
5291
mavwp.MAVWPLoader,
5292
filepath,
5293
target_system=target_system,
5294
target_component=target_component,
5295
)
5296
5297
def sitl_home_string_from_mission(self, filename):
5298
'''return a string of the form "lat,lng,yaw,alt" from the home
5299
location in a mission file'''
5300
return "%s,%s,%s,%s" % self.get_home_tuple_from_mission(filename)
5301
5302
def sitl_home_string_from_mission_filepath(self, filepath):
5303
'''return a string of the form "lat,lng,yaw,alt" from the home
5304
location in a mission file'''
5305
return "%s,%s,%s,%s" % self.get_home_tuple_from_mission_filepath(filepath)
5306
5307
def get_home_tuple_from_mission(self, filename):
5308
'''gets item 0 from the mission file, returns a tuple suitable for
5309
passing to customise_SITL_commandline as --home. Yaw will be
5310
0, so the caller may want to fill that in
5311
'''
5312
return self.get_home_tuple_from_mission_filepath(
5313
os.path.join(testdir, self.current_test_name_directory, filename)
5314
)
5315
5316
def get_home_location_from_mission(self, filename):
5317
(home_lat, home_lon, home_alt, heading) = self.get_home_tuple_from_mission("rover-path-planning-mission.txt")
5318
return mavutil.location(home_lat, home_lon)
5319
5320
def get_home_tuple_from_mission_filepath(self, filepath):
5321
'''gets item 0 from the mission file, returns a tuple suitable for
5322
passing to customise_SITL_commandline as --home. Yaw will be
5323
0, so the caller may want to fill that in
5324
'''
5325
items = self.mission_from_filepath(filepath)
5326
home_item = items[0]
5327
return (home_item.x * 1e-7, home_item.y * 1e-7, home_item.z, 0)
5328
5329
# TODO: rename the following to "upload_mission_from_filepath"
5330
def load_mission_from_filepath(self,
5331
filepath,
5332
target_system=1,
5333
target_component=1,
5334
strict=True,
5335
reset_current_wp=True):
5336
wpoints_int = self.mission_from_filepath(
5337
filepath,
5338
target_system=target_system,
5339
target_component=target_component
5340
)
5341
self.check_mission_upload_download(wpoints_int, strict=strict)
5342
if reset_current_wp:
5343
# ArduPilot doesn't reset the current waypoint by default
5344
# we may be in auto mode and running waypoints, so we
5345
# can't check the current waypoint after resetting it.
5346
self.set_current_waypoint(0, check_afterwards=False)
5347
return len(wpoints_int)
5348
5349
def load_mission_using_mavproxy(self, mavproxy, filename):
5350
return self.load_mission_from_filepath_using_mavproxy(
5351
mavproxy,
5352
self.current_test_name_directory,
5353
filename)
5354
5355
def load_mission_from_filepath_using_mavproxy(self,
5356
mavproxy,
5357
filepath,
5358
filename):
5359
"""Load a mission from a file to flight controller."""
5360
self.progress("Loading mission (%s)" % filename)
5361
path = os.path.join(testdir, filepath, filename)
5362
tstart = self.get_sim_time()
5363
while True:
5364
t2 = self.get_sim_time()
5365
if t2 - tstart > 10:
5366
raise AutoTestTimeoutException("Failed to do waypoint thing")
5367
# the following hack is to get around MAVProxy statustext deduping:
5368
while time.time() - self.last_wp_load < 3:
5369
self.progress("Waiting for MAVProxy de-dupe timer to expire")
5370
self.drain_mav()
5371
time.sleep(0.1)
5372
mavproxy.send('wp load %s\n' % path)
5373
mavproxy.expect('Loaded ([0-9]+) waypoints from')
5374
load_count = mavproxy.match.group(1)
5375
self.last_wp_load = time.time()
5376
mavproxy.expect("Flight plan received")
5377
mavproxy.send('wp list\n')
5378
mavproxy.expect('Requesting ([0-9]+) waypoints')
5379
request_count = mavproxy.match.group(1)
5380
if load_count != request_count:
5381
self.progress("request_count=%s != load_count=%s" %
5382
(request_count, load_count))
5383
continue
5384
mavproxy.expect('Saved ([0-9]+) waypoints to (.+?way.txt)')
5385
save_count = mavproxy.match.group(1)
5386
if save_count != request_count:
5387
raise NotAchievedException("request count != load count")
5388
# warning: this assumes MAVProxy was started in the CWD!
5389
# on the autotest server we invoke autotest.py one-up from
5390
# the git root, like this:
5391
# timelimit 32000 APM/Tools/autotest/autotest.py --timeout=30000 > buildlogs/autotest-output.txt 2>&1
5392
# that means the MAVProxy log files are not reltopdir!
5393
saved_filepath = mavproxy.match.group(2)
5394
saved_filepath = saved_filepath.rstrip()
5395
self.assert_mission_files_same(path, saved_filepath)
5396
break
5397
mavproxy.send('wp status\n')
5398
mavproxy.expect(r'Have (\d+) of (\d+)')
5399
status_have = mavproxy.match.group(1)
5400
status_want = mavproxy.match.group(2)
5401
if status_have != status_want:
5402
raise ValueError("status count mismatch")
5403
if status_have != save_count:
5404
raise ValueError("status have not equal to save count")
5405
5406
wploader = mavwp.MAVWPLoader()
5407
wploader.load(path)
5408
num_wp = wploader.count()
5409
if num_wp != int(status_have):
5410
raise ValueError("num_wp=%u != status_have=%u" %
5411
(num_wp, int(status_have)))
5412
if num_wp == 0:
5413
raise ValueError("No waypoints loaded?!")
5414
5415
return num_wp
5416
5417
def save_mission_to_file_using_mavproxy(self, mavproxy, filename):
5418
"""Save a mission to a file"""
5419
mavproxy.send('wp list\n')
5420
mavproxy.expect('Requesting [0-9]+ waypoints')
5421
mavproxy.send('wp save %s\n' % filename)
5422
mavproxy.expect('Saved ([0-9]+) waypoints')
5423
num_wp = int(mavproxy.match.group(1))
5424
self.progress("num_wp: %d" % num_wp)
5425
return num_wp
5426
5427
def string_for_frame(self, frame):
5428
return mavutil.mavlink.enums["MAV_FRAME"][frame].name
5429
5430
def frames_equivalent(self, f1, f2):
5431
pairs = [
5432
(mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
5433
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT),
5434
(mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5435
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT),
5436
(mavutil.mavlink.MAV_FRAME_GLOBAL,
5437
mavutil.mavlink.MAV_FRAME_GLOBAL_INT),
5438
]
5439
for pair in pairs:
5440
if (f1 == pair[0] and f2 == pair[1]):
5441
return True
5442
if (f1 == pair[1] and f2 == pair[0]):
5443
return True
5444
return f1 == f2
5445
5446
def check_mission_items_same(self,
5447
check_atts,
5448
want,
5449
got,
5450
epsilon=None,
5451
skip_first_item=False,
5452
strict=True):
5453
self.progress("Checking mission items same")
5454
if epsilon is None:
5455
epsilon = 1
5456
if len(want) != len(got):
5457
raise NotAchievedException("Incorrect item count (want=%u got=%u)" % (len(want), len(got)))
5458
self.progress("Checking %u items" % len(want))
5459
for i in range(0, len(want)):
5460
if skip_first_item and i == 0:
5461
continue
5462
item = want[i]
5463
downloaded_item = got[i]
5464
5465
check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']
5466
# z is not preserved
5467
5468
self.progress("Comparing (%s) and (%s)" % (str(item), str(downloaded_item)))
5469
5470
for att in check_atts:
5471
item_val = getattr(item, att)
5472
downloaded_item_val = getattr(downloaded_item, att)
5473
if abs(item_val - downloaded_item_val) > epsilon:
5474
raise NotAchievedException(
5475
"Item %u (%s) has different %s after download want=%s got=%s (got-item=%s)" %
5476
(i, str(item), att, str(item_val), str(downloaded_item_val), str(downloaded_item)))
5477
# for waypoint items ensure z and frame are preserved:
5478
self.progress("Type is %u" % got[0].mission_type)
5479
if got[0].mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
5480
item_val = getattr(item, 'frame')
5481
downloaded_item_val = getattr(downloaded_item, 'frame')
5482
# if you are thinking of adding another, "don't annoy
5483
# me, I know missions aren't troundtripped" non-strict
5484
# thing here, DON'T do it without first checking "def
5485
# assert_mission_files_same"; it makes the same checks
5486
# as will be needed here eventually.
5487
if ((strict or self.ardupilot_stores_frame_for_cmd(getattr(item, 'command'))) and
5488
not self.frames_equivalent(item_val, downloaded_item_val)):
5489
raise NotAchievedException("Frame not same (got=%s want=%s)" %
5490
(self.string_for_frame(downloaded_item_val),
5491
self.string_for_frame(item_val)))
5492
if downloaded_item.z == 0:
5493
delta = abs(item.z)
5494
else:
5495
delta = 1 - abs(item.z / downloaded_item.z)
5496
if delta > 0.01: # error should be less than 1 mm, but float precision issues in Python...
5497
raise NotAchievedException("Z not preserved (got=%f want=%f delta=%f%%)" %
5498
(downloaded_item.z, item.z, delta))
5499
5500
def check_fence_items_same(self, want, got, strict=True):
5501
check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1']
5502
return self.check_mission_items_same(check_atts, want, got, strict=strict)
5503
5504
def check_mission_waypoint_items_same(self, want, got, strict=True):
5505
check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']
5506
return self.check_mission_items_same(check_atts, want, got, skip_first_item=True, strict=strict)
5507
5508
def check_mission_item_upload_download(self, items, itype, mission_type, strict=True):
5509
self.progress("check %s upload/download: upload %u items" %
5510
(itype, len(items),))
5511
self.upload_using_mission_protocol(mission_type, items)
5512
self.progress("check %s upload/download: download items" % itype)
5513
downloaded_items = self.download_using_mission_protocol(mission_type)
5514
if len(items) != len(downloaded_items):
5515
raise NotAchievedException("Did not download same number of items as uploaded want=%u got=%u" %
5516
(len(items), len(downloaded_items)))
5517
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_FENCE:
5518
self.check_fence_items_same(items, downloaded_items, strict=strict)
5519
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
5520
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
5521
elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY:
5522
self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict)
5523
else:
5524
raise NotAchievedException("Unhandled")
5525
5526
def check_fence_upload_download(self, items):
5527
self.check_mission_item_upload_download(
5528
items,
5529
"fence",
5530
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
5531
if self.use_map and self.mavproxy is not None:
5532
self.mavproxy.send('fence list\n')
5533
5534
def check_mission_upload_download(self, items, strict=True):
5535
self.check_mission_item_upload_download(
5536
items,
5537
"waypoints",
5538
mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
5539
strict=strict)
5540
if self.use_map and self.mavproxy is not None:
5541
self.mavproxy.send('wp list\n')
5542
5543
def check_rally_upload_download(self, items):
5544
self.check_mission_item_upload_download(
5545
items,
5546
"rally",
5547
mavutil.mavlink.MAV_MISSION_TYPE_RALLY
5548
)
5549
if self.use_map and self.mavproxy is not None:
5550
self.mavproxy.send('rally list\n')
5551
5552
def check_dflog_message_rates(self, log_filepath, message_rates):
5553
reader = self.dfreader_for_path(log_filepath)
5554
5555
counts = {}
5556
first = None
5557
while True:
5558
m = reader.recv_match()
5559
if m is None:
5560
break
5561
if (m.fmt.instance_field is not None and
5562
getattr(m, m.fmt.instance_field) != 0):
5563
continue
5564
5565
t = m.get_type()
5566
# print("t=%s" % str(t))
5567
if t not in counts:
5568
counts[t] = 0
5569
counts[t] += 1
5570
5571
if hasattr(m, 'TimeUS'):
5572
if first is None:
5573
first = m
5574
last = m
5575
5576
if first is None:
5577
raise NotAchievedException("Did not get any messages")
5578
delta_time_us = last.TimeUS - first.TimeUS
5579
5580
for (t, want_rate) in message_rates.items():
5581
if t not in counts:
5582
raise NotAchievedException("Wanted %s but got none" % t)
5583
self.progress("Got (%u) in (%uus)" % (counts[t], delta_time_us))
5584
got_rate = float(counts[t]) / delta_time_us * 1000000
5585
5586
if abs(want_rate - got_rate) > 5:
5587
raise NotAchievedException("Not getting %s data at wanted rate want=%f got=%f" %
5588
(t, want_rate, got_rate))
5589
5590
def generate_rate_sample_log(self):
5591
self.reboot_sitl()
5592
self.wait_ready_to_arm()
5593
self.delay_sim_time(20)
5594
path = self.current_onboard_log_filepath()
5595
self.progress("Rate sample log (%s)" % path)
5596
self.reboot_sitl()
5597
return path
5598
5599
def rc_defaults(self):
5600
return {
5601
1: 1500,
5602
2: 1500,
5603
3: 1500,
5604
4: 1500,
5605
5: 1500,
5606
6: 1500,
5607
7: 1500,
5608
8: 1500,
5609
9: 1500,
5610
10: 1500,
5611
11: 1500,
5612
12: 1500,
5613
13: 1500,
5614
14: 1500,
5615
15: 1500,
5616
16: 1500,
5617
}
5618
5619
def set_rc_from_map(self, _map, timeout=20):
5620
map_copy = _map.copy()
5621
for v in map_copy.values():
5622
if not isinstance(v, int):
5623
raise NotAchievedException("RC values must be integers")
5624
self.rc_queue.put(map_copy)
5625
5626
if self.rc_thread is None:
5627
self.rc_thread = threading.Thread(target=self.rc_thread_main, name='RC')
5628
if self.rc_thread is None:
5629
raise NotAchievedException("Could not create thread")
5630
self.rc_thread.start()
5631
5632
tstart = self.get_sim_time()
5633
while True:
5634
if tstart - self.get_sim_time_cached() > timeout:
5635
raise NotAchievedException("Failed to set RC values")
5636
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=1)
5637
if m is None:
5638
continue
5639
bad_channels = ""
5640
for chan in map_copy:
5641
chan_pwm = getattr(m, "chan" + str(chan) + "_raw")
5642
if chan_pwm != map_copy[chan]:
5643
bad_channels += " (ch=%u want=%u got=%u)" % (chan, map_copy[chan], chan_pwm)
5644
break
5645
if len(bad_channels) == 0:
5646
self.progress("RC values good")
5647
break
5648
self.progress("RC values bad:%s" % bad_channels)
5649
if not self.rc_thread.is_alive():
5650
self.rc_thread = None
5651
raise ValueError("RC thread is dead") # FIXME: type
5652
5653
def rc_thread_main(self):
5654
chan16 = [1000] * 16
5655
5656
sitl_output = mavutil.mavudp("127.0.0.1:%u" % self.sitl_rcin_port(), input=False)
5657
buf = None
5658
5659
while True:
5660
if self.rc_thread_should_quit:
5661
break
5662
5663
# the 0.05 here means we're updating the RC values into
5664
# the autopilot at 20Hz - that's our 50Hz wallclock, , not
5665
# the autopilot's simulated 20Hz, so if speedup is 10 the
5666
# autopilot will see ~2Hz.
5667
timeout = 0.02
5668
# ... and 2Hz is too slow when we now run at 100x speedup:
5669
timeout /= (self.speedup / 10.0)
5670
5671
try:
5672
map_copy = self.rc_queue.get(timeout=timeout)
5673
5674
# 16 packed entries:
5675
for i in range(1, 17):
5676
if i in map_copy:
5677
chan16[i-1] = map_copy[i]
5678
5679
except Queue.Empty:
5680
pass
5681
5682
buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)
5683
5684
if buf is None:
5685
continue
5686
5687
sitl_output.write(buf)
5688
5689
def set_rc_default(self):
5690
"""Setup all simulated RC control to 1500."""
5691
_defaults = self.rc_defaults()
5692
self.set_rc_from_map(_defaults)
5693
5694
def check_rc_defaults(self):
5695
"""Ensure all rc outputs are at defaults"""
5696
self.do_timesync_roundtrip()
5697
_defaults = self.rc_defaults()
5698
m = self.assert_receive_message('RC_CHANNELS', timeout=5)
5699
need_set = {}
5700
for chan in _defaults:
5701
default_value = _defaults[chan]
5702
current_value = getattr(m, "chan" + str(chan) + "_raw")
5703
if default_value != current_value:
5704
self.progress("chan=%u needs resetting is=%u want=%u" %
5705
(chan, current_value, default_value))
5706
need_set[chan] = default_value
5707
self.set_rc_from_map(need_set)
5708
5709
def set_rc(self, chan, pwm, timeout=20):
5710
"""Setup a simulated RC control to a PWM value"""
5711
self.set_rc_from_map({chan: pwm}, timeout=timeout)
5712
5713
def set_servo(self, chan, pwm):
5714
"""Replicate the functionality of MAVProxy: servo set <ch> <pwm>"""
5715
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=chan, p2=pwm)
5716
5717
def location_offset_ne(self, location, north, east):
5718
'''move location in metres'''
5719
print("old: %f %f" % (location.lat, location.lng))
5720
(lat, lng) = mp_util.gps_offset(location.lat, location.lng, east, north)
5721
location.lat = lat
5722
location.lng = lng
5723
print("new: %f %f" % (location.lat, location.lng))
5724
5725
def home_relative_loc_ne(self, n, e):
5726
ret = self.home_position_as_mav_location()
5727
self.location_offset_ne(ret, n, e)
5728
return ret
5729
5730
def home_relative_loc_neu(self, n, e, u):
5731
ret = self.home_position_as_mav_location()
5732
self.location_offset_ne(ret, n, e)
5733
ret.alt += u
5734
return ret
5735
5736
def zero_throttle(self):
5737
"""Set throttle to zero."""
5738
if self.is_rover():
5739
self.set_rc(3, 1500)
5740
else:
5741
self.set_rc(3, 1000)
5742
5743
def set_output_to_max(self, chan):
5744
"""Set output to max with RC Radio taking into account REVERSED parameter."""
5745
is_reversed = self.get_parameter("RC%u_REVERSED" % chan)
5746
out_max = int(self.get_parameter("RC%u_MAX" % chan))
5747
out_min = int(self.get_parameter("RC%u_MIN" % chan))
5748
if is_reversed == 0:
5749
self.set_rc(chan, out_max)
5750
else:
5751
self.set_rc(chan, out_min)
5752
5753
def set_output_to_min(self, chan):
5754
"""Set output to min with RC Radio taking into account REVERSED parameter."""
5755
is_reversed = self.get_parameter("RC%u_REVERSED" % chan)
5756
out_max = int(self.get_parameter("RC%u_MAX" % chan))
5757
out_min = int(self.get_parameter("RC%u_MIN" % chan))
5758
if is_reversed == 0:
5759
self.set_rc(chan, out_min)
5760
else:
5761
self.set_rc(chan, out_max)
5762
5763
def set_output_to_trim(self, chan):
5764
"""Set output to trim with RC Radio."""
5765
out_trim = int(self.get_parameter("RC%u_TRIM" % chan))
5766
self.set_rc(chan, out_trim)
5767
5768
def get_stick_arming_channel(self):
5769
"""Return the Rudder channel number as set in parameter."""
5770
raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
5771
5772
def get_disarm_delay(self):
5773
"""Return disarm delay value."""
5774
raise ErrorException("Disarm delay is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
5775
5776
def arming_test_mission(self):
5777
"""Load arming test mission.
5778
This mission is used to allow to change mode to AUTO. For each vehicle
5779
it get an unlimited wait waypoint and the starting takeoff if needed."""
5780
if self.is_rover() or self.is_plane() or self.is_sub():
5781
return os.path.join(testdir, self.current_test_name_directory + "test_arming.txt")
5782
else:
5783
return None
5784
5785
def set_safetyswitch_on(self, **kwargs):
5786
self.set_safetyswitch(1, **kwargs)
5787
5788
def set_safetyswitch_off(self, **kwargs):
5789
self.set_safetyswitch(0, **kwargs)
5790
5791
def set_safetyswitch(self, value, target_system=1, target_component=1):
5792
self.mav.mav.set_mode_send(
5793
target_system,
5794
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
5795
value)
5796
self.wait_sensor_state(
5797
mavutil.mavlink.MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,
5798
True, not value, True,
5799
verbose=True,
5800
timeout=30
5801
)
5802
5803
def armed(self):
5804
"""Return True if vehicle is armed and safetyoff"""
5805
m = self.wait_heartbeat()
5806
return (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED) != 0
5807
5808
def send_mavlink_arm_command(self):
5809
self.send_cmd(
5810
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5811
p1=1, # ARM
5812
)
5813
5814
def send_mavlink_disarm_command(self):
5815
self.send_cmd(
5816
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5817
p1=0, # DISARM
5818
)
5819
5820
def send_mavlink_run_prearms_command(self):
5821
self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS)
5822
5823
def analog_rangefinder_parameters(self):
5824
return {
5825
"RNGFND1_TYPE": 1,
5826
"RNGFND1_MIN_CM": 0,
5827
"RNGFND1_MAX_CM": 4000,
5828
"RNGFND1_SCALING": 12.12,
5829
"RNGFND1_PIN": 0,
5830
}
5831
5832
def set_analog_rangefinder_parameters(self):
5833
self.set_parameters(self.analog_rangefinder_parameters())
5834
5835
def send_debug_trap(self, timeout=6000):
5836
self.progress("Sending trap to autopilot")
5837
self.run_cmd(
5838
mavutil.mavlink.MAV_CMD_DEBUG_TRAP,
5839
p1=32451, # magic number to trap
5840
timeout=timeout,
5841
)
5842
5843
def try_arm(self, result=True, expect_msg=None, timeout=60):
5844
"""Send Arming command, wait for the expected result and statustext."""
5845
self.progress("Try arming and wait for expected result")
5846
self.drain_mav()
5847
self.run_cmd(
5848
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5849
p1=1, # ARM
5850
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED if result else mavutil.mavlink.MAV_RESULT_FAILED,
5851
timeout=timeout,
5852
)
5853
if expect_msg is not None:
5854
self.wait_statustext(
5855
expect_msg,
5856
timeout=timeout,
5857
the_function=lambda: self.send_cmd(
5858
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5859
p1=1, # ARM
5860
target_sysid=None,
5861
target_compid=None,
5862
))
5863
5864
def arm_vehicle(self, timeout=20, force=False):
5865
"""Arm vehicle with mavlink arm message."""
5866
self.progress("Arm motors with MAVLink cmd")
5867
p2 = 0
5868
if force:
5869
p2 = 2989
5870
try:
5871
self.run_cmd(
5872
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5873
p1=1, # ARM
5874
p2=p2,
5875
timeout=timeout,
5876
)
5877
except ValueError as e:
5878
# statustexts are queued; give it a second to arrive:
5879
self.delay_sim_time(5)
5880
raise e
5881
try:
5882
self.wait_armed()
5883
except AutoTestTimeoutException:
5884
raise AutoTestTimeoutException("Failed to ARM with mavlink")
5885
return True
5886
5887
def wait_armed(self, timeout=20):
5888
tstart = self.get_sim_time()
5889
while self.get_sim_time_cached() - tstart < timeout:
5890
self.wait_heartbeat(drain_mav=False)
5891
if self.mav.motors_armed():
5892
self.progress("Motors ARMED")
5893
return
5894
raise AutoTestTimeoutException("Did not become armed")
5895
5896
def disarm_vehicle(self, timeout=60, force=False):
5897
"""Disarm vehicle with mavlink disarm message."""
5898
self.progress("Disarm motors with MAVLink cmd")
5899
p2 = 0
5900
if force:
5901
p2 = 21196 # magic force disarm value
5902
self.run_cmd(
5903
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5904
p1=0, # DISARM
5905
p2=p2,
5906
timeout=timeout,
5907
)
5908
self.wait_disarmed()
5909
5910
def disarm_vehicle_expect_fail(self):
5911
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
5912
self.progress("Disarm - expect to fail")
5913
self.run_cmd(
5914
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
5915
p1=0, # DISARM
5916
timeout=10,
5917
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
5918
)
5919
self.progress("Disarm - forced")
5920
self.disarm_vehicle(force=True)
5921
5922
def wait_disarmed_default_wait_time(self):
5923
return 30
5924
5925
def wait_disarmed(self, timeout=None, tstart=None):
5926
if timeout is None:
5927
timeout = self.wait_disarmed_default_wait_time()
5928
self.progress("Waiting for DISARM")
5929
if tstart is None:
5930
tstart = self.get_sim_time()
5931
last_print_time = 0
5932
while True:
5933
now = self.get_sim_time_cached()
5934
delta = now - tstart
5935
if delta > timeout:
5936
raise AutoTestTimeoutException("Failed to DISARM within %fs" %
5937
(timeout,))
5938
if now - last_print_time > 1:
5939
self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout))
5940
last_print_time = now
5941
msg = self.wait_heartbeat(quiet=True)
5942
if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
5943
# still armed
5944
continue
5945
self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %
5946
(delta, timeout))
5947
return
5948
5949
def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'):
5950
'''wait for an attitude (degrees)'''
5951
if desroll is None and despitch is None:
5952
raise ValueError("despitch or desroll must be supplied")
5953
tstart = self.get_sim_time()
5954
while True:
5955
if self.get_sim_time_cached() - tstart > timeout:
5956
raise AutoTestTimeoutException("Failed to achieve attitude")
5957
m = self.assert_receive_message(message_type, timeout=60)
5958
roll_deg = math.degrees(m.roll)
5959
pitch_deg = math.degrees(m.pitch)
5960
self.progress("wait_att: roll=%f desroll=%s pitch=%f despitch=%s" %
5961
(roll_deg, desroll, pitch_deg, despitch))
5962
if desroll is not None and abs(roll_deg - desroll) > tolerance:
5963
continue
5964
if despitch is not None and abs(pitch_deg - despitch) > tolerance:
5965
continue
5966
return
5967
5968
def wait_attitude_quaternion(self,
5969
desroll=None,
5970
despitch=None,
5971
timeout=2,
5972
tolerance=10,
5973
message_type='ATTITUDE_QUATERNION'):
5974
'''wait for an attitude (degrees)'''
5975
if desroll is None and despitch is None:
5976
raise ValueError("despitch or desroll must be supplied")
5977
tstart = self.get_sim_time()
5978
while True:
5979
if self.get_sim_time_cached() - tstart > timeout:
5980
raise AutoTestTimeoutException("Failed to achieve attitude")
5981
m = self.poll_message(message_type)
5982
q = quaternion.Quaternion([m.q1, m.q2, m.q3, m.q4])
5983
euler = q.euler
5984
roll = euler[0]
5985
pitch = euler[1]
5986
roll_deg = math.degrees(roll)
5987
pitch_deg = math.degrees(pitch)
5988
self.progress("wait_att_quat: roll=%f desroll=%s pitch=%f despitch=%s" %
5989
(roll_deg, desroll, pitch_deg, despitch))
5990
if desroll is not None and abs(roll_deg - desroll) > tolerance:
5991
continue
5992
if despitch is not None and abs(pitch_deg - despitch) > tolerance:
5993
continue
5994
self.progress("wait_att_quat: achieved")
5995
return
5996
5997
def CPUFailsafe(self):
5998
'''Ensure we do something appropriate when the main loop stops'''
5999
# Most vehicles just disarm on failsafe
6000
# customising the SITL commandline ensures the process will
6001
# get stopped/started at the end of the test
6002
if self.frame is None:
6003
raise ValueError("Frame is none?")
6004
self.customise_SITL_commandline([])
6005
self.wait_ready_to_arm()
6006
self.arm_vehicle()
6007
self.progress("Sending enter-cpu-lockup")
6008
# when we're in CPU lockup we don't get SYSTEM_TIME messages,
6009
# so get_sim_time breaks:
6010
tstart = self.get_sim_time()
6011
self.send_cmd_enter_cpu_lockup()
6012
self.wait_disarmed(timeout=5, tstart=tstart)
6013
# we're not getting SYSTEM_TIME messages at this point.... and
6014
# we're in a weird state where the vehicle is armed but the
6015
# motors are not, and we can't disarm further because Copter
6016
# looks at whether its *motors* are armed as part of its
6017
# disarm process.
6018
self.reset_SITL_commandline()
6019
6020
def cpufailsafe_wait_servo_channel_value(self, channel, value, timeout=30):
6021
'''we get restricted messages while doing cpufailsafe, this working then'''
6022
start = time.time()
6023
while True:
6024
if time.time() - start > timeout:
6025
raise NotAchievedException("Did not achieve value")
6026
m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)
6027
channel_field = "servo%u_raw" % channel
6028
m_value = getattr(m, channel_field, None)
6029
self.progress("Servo%u=%u want=%u" % (channel, m_value, value))
6030
if m_value == value:
6031
break
6032
6033
def plane_CPUFailsafe(self):
6034
'''In lockup Plane should copy RC inputs to RC outputs'''
6035
# customising the SITL commandline ensures the process will
6036
# get stopped/started at the end of the test
6037
self.customise_SITL_commandline([])
6038
self.wait_ready_to_arm()
6039
self.arm_vehicle()
6040
self.progress("Sending enter-cpu-lockup")
6041
# when we're in CPU lockup we don't get SYSTEM_TIME messages,
6042
# so get_sim_time breaks:
6043
self.send_cmd_enter_cpu_lockup()
6044
start_time = time.time() # not sim time!
6045
self.context_push()
6046
self.context_collect("STATUSTEXT")
6047
while True:
6048
want = "Initialising ArduPilot"
6049
if time.time() - start_time > 30:
6050
raise NotAchievedException("Did not get %s" % want)
6051
# we still need to parse the incoming messages:
6052
try:
6053
self.wait_statustext(want, timeout=0.1, check_context=True, wallclock_timeout=1)
6054
break
6055
except AutoTestTimeoutException:
6056
pass
6057
self.context_pop()
6058
# Different scaling for RC input and servo output means the
6059
# servo output value isn't the rc input value:
6060
self.progress("Setting RC to 1200")
6061
self.rc_queue.put({2: 1200})
6062
self.progress("Waiting for servo of 1260")
6063
self.cpufailsafe_wait_servo_channel_value(2, 1260)
6064
self.rc_queue.put({2: 1700})
6065
self.cpufailsafe_wait_servo_channel_value(2, 1660)
6066
self.reset_SITL_commandline()
6067
6068
def mavproxy_arm_vehicle(self, mavproxy):
6069
"""Arm vehicle with mavlink arm message send from MAVProxy."""
6070
self.progress("Arm motors with MavProxy")
6071
mavproxy.send('arm throttle\n')
6072
self.wait_armed()
6073
self.progress("ARMED")
6074
return True
6075
6076
def mavproxy_disarm_vehicle(self, mavproxy):
6077
"""Disarm vehicle with mavlink disarm message send from MAVProxy."""
6078
self.progress("Disarm motors with MavProxy")
6079
mavproxy.send('disarm\n')
6080
self.wait_disarmed()
6081
6082
def arm_motors_with_rc_input(self, timeout=20):
6083
"""Arm motors with radio."""
6084
self.progress("Arm motors with radio")
6085
self.set_output_to_max(self.get_stick_arming_channel())
6086
tstart = self.get_sim_time()
6087
while True:
6088
self.wait_heartbeat()
6089
tdelta = self.get_sim_time_cached() - tstart
6090
if self.mav.motors_armed():
6091
self.progress("MOTORS ARMED OK WITH RADIO")
6092
self.set_output_to_trim(self.get_stick_arming_channel())
6093
self.progress("Arm in %ss" % tdelta) # TODO check arming time
6094
return
6095
self.progress("Not armed after %f seconds" % (tdelta))
6096
if tdelta > timeout:
6097
break
6098
self.set_output_to_trim(self.get_stick_arming_channel())
6099
raise NotAchievedException("Failed to ARM with radio")
6100
6101
def disarm_motors_with_rc_input(self, timeout=20, watch_for_disabled=False):
6102
"""Disarm motors with radio."""
6103
self.progress("Disarm motors with radio")
6104
self.do_timesync_roundtrip()
6105
self.context_push()
6106
self.context_collect('STATUSTEXT')
6107
self.set_output_to_min(self.get_stick_arming_channel())
6108
tstart = self.get_sim_time()
6109
ret = False
6110
while self.get_sim_time_cached() < tstart + timeout:
6111
self.wait_heartbeat()
6112
if not self.mav.motors_armed():
6113
disarm_delay = self.get_sim_time_cached() - tstart
6114
self.progress("MOTORS DISARMED OK WITH RADIO (in %ss)" % disarm_delay)
6115
ret = True
6116
break
6117
if self.statustext_in_collections("Rudder disarm: disabled"):
6118
self.progress("Found 'Rudder disarm: disabled' in statustext")
6119
break
6120
self.context_clear_collection('STATUSTEXT')
6121
self.set_output_to_trim(self.get_stick_arming_channel())
6122
self.context_pop()
6123
if not ret:
6124
raise NotAchievedException("Failed to DISARM with RC input")
6125
6126
def arm_motors_with_switch(self, switch_chan, timeout=20):
6127
"""Arm motors with switch."""
6128
self.progress("Arm motors with switch %d" % switch_chan)
6129
self.set_rc(switch_chan, 2000)
6130
tstart = self.get_sim_time()
6131
while self.get_sim_time_cached() - tstart < timeout:
6132
self.wait_heartbeat()
6133
if self.mav.motors_armed():
6134
self.progress("MOTORS ARMED OK WITH SWITCH")
6135
return
6136
raise NotAchievedException("Failed to ARM with switch")
6137
6138
def disarm_motors_with_switch(self, switch_chan, timeout=20):
6139
"""Disarm motors with switch."""
6140
self.progress("Disarm motors with switch %d" % switch_chan)
6141
self.set_rc(switch_chan, 1000)
6142
tstart = self.get_sim_time()
6143
while self.get_sim_time_cached() < tstart + timeout:
6144
self.wait_heartbeat()
6145
if not self.mav.motors_armed():
6146
self.progress("MOTORS DISARMED OK WITH SWITCH")
6147
return
6148
raise NotAchievedException("Failed to DISARM with switch")
6149
6150
def disarm_wait(self, timeout=10):
6151
tstart = self.get_sim_time()
6152
while True:
6153
if self.get_sim_time_cached() - tstart > timeout:
6154
raise NotAchievedException("Did not disarm")
6155
self.wait_heartbeat()
6156
if not self.mav.motors_armed():
6157
return
6158
6159
def wait_autodisarm_motors(self):
6160
"""Wait for Autodisarm motors within disarm delay
6161
this feature is only available in copter (DISARM_DELAY) and plane (LAND_DISARMDELAY)."""
6162
self.progress("Wait autodisarming motors")
6163
disarm_delay = self.get_disarm_delay()
6164
tstart = self.get_sim_time()
6165
timeout = disarm_delay * 2
6166
while self.get_sim_time_cached() < tstart + timeout:
6167
self.wait_heartbeat()
6168
if not self.mav.motors_armed():
6169
disarm_time = self.get_sim_time_cached() - tstart
6170
self.progress("MOTORS AUTODISARMED")
6171
self.progress("Autodisarm in %ss, expect less than %ss" % (disarm_time, disarm_delay))
6172
return disarm_time <= disarm_delay
6173
raise AutoTestTimeoutException("Failed to AUTODISARM")
6174
6175
def set_autodisarm_delay(self, delay):
6176
"""Set autodisarm delay"""
6177
raise ErrorException("Auto disarm is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame))
6178
6179
@staticmethod
6180
def should_fetch_all_for_parameter_change(param_name):
6181
return False # FIXME: if we allow MAVProxy then allow this
6182
if fnmatch.fnmatch(param_name, "*_ENABLE") or fnmatch.fnmatch(param_name, "*_ENABLED"):
6183
return True
6184
if param_name in ["ARSPD_TYPE",
6185
"ARSPD2_TYPE",
6186
"BATT2_MONITOR",
6187
"CAN_DRIVER",
6188
"COMPASS_PMOT_EN",
6189
"OSD_TYPE",
6190
"RSSI_TYPE",
6191
"WENC_TYPE"]:
6192
return True
6193
return False
6194
6195
def send_set_parameter_direct(self, name, value):
6196
self.mav.mav.param_set_send(self.sysid_thismav(),
6197
1,
6198
name.encode('ascii'),
6199
value,
6200
mavutil.mavlink.MAV_PARAM_TYPE_REAL32)
6201
6202
def send_set_parameter_mavproxy(self, name, value):
6203
self.mavproxy.send("param set %s %s\n" % (name, str(value)))
6204
6205
def send_set_parameter(self, name, value, verbose=False):
6206
if verbose:
6207
self.progress("Send set param for (%s) (%f)" % (name, value))
6208
return self.send_set_parameter_direct(name, value)
6209
6210
def set_parameter(self, name, value, **kwargs):
6211
self.set_parameters({name: value}, **kwargs)
6212
6213
def set_parameters(self, parameters, add_to_context=True, epsilon_pct=0.00001, verbose=True, attempts=None):
6214
"""Set parameters from vehicle."""
6215
6216
want = copy.copy(parameters)
6217
self.progress("set_parameters: (%s)" % str(want))
6218
self.drain_mav()
6219
if len(want) == 0:
6220
return
6221
6222
if attempts is None:
6223
# we can easily fill ArduPilot's param-set/param-get queue
6224
# which is quite short. So we retry *a lot*.
6225
attempts = len(want) * 10
6226
6227
param_value_messages = []
6228
6229
def add_param_value(mav, m):
6230
t = m.get_type()
6231
if t != "PARAM_VALUE":
6232
return
6233
param_value_messages.append(m)
6234
6235
self.install_message_hook(add_param_value)
6236
6237
original_values = {}
6238
autopilot_values = {}
6239
for i in range(attempts):
6240
self.drain_mav(quiet=True)
6241
self.drain_all_pexpects()
6242
received = set()
6243
for (name, value) in want.items():
6244
if verbose:
6245
self.progress("%s want=%f autopilot=%s (attempt=%u/%u)" %
6246
(name, value, autopilot_values.get(name, 'None'), i+1, attempts))
6247
if name not in autopilot_values:
6248
if verbose:
6249
self.progress("Requesting (%s)" % (name,))
6250
self.send_get_parameter_direct(name)
6251
continue
6252
delta = abs(autopilot_values[name] - value)
6253
if delta <= epsilon_pct*0.01*abs(value):
6254
# correct value
6255
self.progress("%s is now %f" % (name, autopilot_values[name]))
6256
if add_to_context:
6257
context_param_name_list = [p[0] for p in self.context_get().parameters]
6258
if name.upper() not in context_param_name_list:
6259
self.context_get().parameters.append((name, original_values[name]))
6260
received.add(name)
6261
continue
6262
self.progress("Sending set (%s) to (%f) (old=%f)" % (name, value, original_values[name]))
6263
self.send_set_parameter_direct(name, value)
6264
for name in received:
6265
del want[name]
6266
if len(want):
6267
# problem here is that a reboot can happen after we
6268
# send the request but before we receive the reply:
6269
try:
6270
self.do_timesync_roundtrip(quiet=True)
6271
except AutoTestTimeoutException:
6272
pass
6273
for m in param_value_messages:
6274
if m.param_id in want:
6275
self.progress("Received wanted PARAM_VALUE %s=%f" %
6276
(str(m.param_id), m.param_value))
6277
autopilot_values[m.param_id] = m.param_value
6278
if m.param_id not in original_values:
6279
original_values[m.param_id] = m.param_value
6280
param_value_messages = []
6281
6282
self.remove_message_hook(add_param_value)
6283
6284
if len(want) == 0:
6285
return
6286
raise ValueError("Failed to set parameters (%s)" % want)
6287
6288
def get_parameter(self, *args, **kwargs):
6289
return self.get_parameter_direct(*args, **kwargs)
6290
6291
def send_get_parameter_direct(self, name):
6292
encname = name
6293
if sys.version_info.major >= 3 and not isinstance(encname, bytes):
6294
encname = bytes(encname, 'ascii')
6295
self.mav.mav.param_request_read_send(self.sysid_thismav(),
6296
1,
6297
encname,
6298
-1)
6299
6300
def get_parameter_direct(self, name, attempts=1, timeout=60, verbose=True, timeout_in_wallclock=False):
6301
while attempts > 0:
6302
attempts -= 1
6303
if verbose:
6304
self.progress("Sending param_request_read for (%s)" % name)
6305
# we MUST parse here or collections fail where we need
6306
# them to work!
6307
self.drain_mav(quiet=True)
6308
if timeout_in_wallclock:
6309
tstart = time.time()
6310
else:
6311
tstart = self.get_sim_time()
6312
self.send_get_parameter_direct(name)
6313
while True:
6314
if timeout_in_wallclock:
6315
now = time.time()
6316
else:
6317
now = self.get_sim_time_cached()
6318
if tstart > now:
6319
self.progress("Time wrap detected")
6320
# we're going to have to send another request...
6321
break
6322
delta_time = now - tstart
6323
if delta_time > timeout:
6324
break
6325
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=0.1)
6326
if verbose:
6327
self.progress("get_parameter(%s): %s" % (name, str(m), ))
6328
if m is None:
6329
continue
6330
if m.param_id == name:
6331
if delta_time > 5:
6332
self.progress("Long time to get parameter: %fs" % (delta_time,))
6333
return m.param_value
6334
if verbose:
6335
self.progress("(%s) != (%s)" % (m.param_id, name,))
6336
raise NotAchievedException("Failed to retrieve parameter (%s)" % name)
6337
6338
def get_parameter_mavproxy(self, mavproxy, name, attempts=1, timeout=60):
6339
"""Get parameters from vehicle."""
6340
for i in range(0, attempts):
6341
mavproxy.send("param fetch %s\n" % name)
6342
try:
6343
mavproxy.expect("%s = ([-0-9.]*)\r\n" % (name,), timeout=timeout/attempts)
6344
try:
6345
# sometimes race conditions garble the MAVProxy output
6346
ret = float(mavproxy.match.group(1))
6347
except ValueError:
6348
continue
6349
return ret
6350
except pexpect.TIMEOUT:
6351
pass
6352
raise NotAchievedException("Failed to retrieve parameter (%s)" % name)
6353
6354
def get_parameters(self, some_list, **kwargs):
6355
ret = {}
6356
6357
for n in some_list:
6358
ret[n] = self.get_parameter(n, **kwargs)
6359
6360
return ret
6361
6362
def context_get(self):
6363
"""Get Saved parameters."""
6364
return self.contexts[-1]
6365
6366
def context_push(self):
6367
"""Save a copy of the parameters."""
6368
context = Context()
6369
self.contexts.append(context)
6370
# add a message hook so we can collect messages conveniently:
6371
6372
def mh(mav, m):
6373
t = m.get_type()
6374
if t in context.collections:
6375
context.collections[t].append(m)
6376
self.install_message_hook_context(mh)
6377
6378
def context_collect(self, msg_type):
6379
'''start collecting messages of type msg_type into context collection'''
6380
context = self.context_get()
6381
if msg_type in context.collections:
6382
return
6383
context.collections[msg_type] = []
6384
6385
def context_collection(self, msg_type):
6386
'''return messages in collection'''
6387
context = self.context_get()
6388
if msg_type not in context.collections:
6389
raise NotAchievedException("Not collecting (%s)" % str(msg_type))
6390
return context.collections[msg_type]
6391
6392
def context_clear_collection(self, msg_type):
6393
'''clear collection of message type msg_type'''
6394
context = self.context_get()
6395
if msg_type not in context.collections:
6396
raise NotAchievedException("Not collecting (%s)" % str(msg_type))
6397
context.collections[msg_type] = []
6398
6399
def context_stop_collecting(self, msg_type):
6400
'''stop collecting messages of type msg_type in context collection. Returns the collected messages'''
6401
context = self.context_get()
6402
if msg_type not in context.collections:
6403
raise Exception("Not collecting %s" % str(msg_type))
6404
ret = context.collections[msg_type]
6405
del context.collections[msg_type]
6406
return ret
6407
6408
def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False):
6409
"""Set parameters to origin values in reverse order."""
6410
dead = self.contexts.pop()
6411
# remove hooks first; these hooks can raise exceptions which
6412
# we really don't want...
6413
if not hooks_already_removed:
6414
for hook in dead.message_hooks:
6415
self.remove_message_hook(hook)
6416
for script in dead.installed_scripts:
6417
self.remove_installed_script(script)
6418
for (message_id, rate_hz) in dead.overridden_message_rates.items():
6419
self.set_message_rate_hz(message_id, rate_hz)
6420
for module in dead.installed_modules:
6421
print("Removing module (%s)" % module)
6422
self.remove_installed_modules(module)
6423
if dead.sitl_commandline_customised and len(self.contexts):
6424
self.contexts[-1].sitl_commandline_customised = True
6425
6426
dead_parameters_dict = {}
6427
for p in dead.parameters:
6428
dead_parameters_dict[p[0]] = p[1]
6429
if process_interaction_allowed:
6430
self.set_parameters(dead_parameters_dict, add_to_context=False)
6431
6432
if getattr(self, "old_binary", None) is not None:
6433
self.stop_SITL()
6434
with open(self.binary, "wb") as f:
6435
f.write(self.old_binary)
6436
f.close()
6437
self.start_SITL(wipe=False)
6438
self.set_streamrate(self.sitl_streamrate())
6439
elif dead.reboot_sitl_was_done:
6440
self.progress("Doing implicit context-pop reboot")
6441
self.reboot_sitl(mark_context=False)
6442
6443
# the following method is broken under Python2; can't **build_opts
6444
# def context_start_custom_binary(self, extra_defines={}):
6445
# # grab copy of current binary:
6446
# context = self.context_get()
6447
# if getattr(context, "old_binary", None) is not None:
6448
# raise ValueError("Not nestable at the moment")
6449
# with open(self.binary, "rb") as f:
6450
# self.old_binary = f.read()
6451
# f.close()
6452
# build_opts = copy.copy(self.build_opts)
6453
# build_opts["extra_defines"] = extra_defines
6454
# util.build_SITL(
6455
# 'bin/arducopter', # FIXME!
6456
# **build_opts,
6457
# )
6458
# self.stop_SITL()
6459
# self.start_SITL(wipe=False)
6460
# self.set_streamrate(self.sitl_streamrate())
6461
6462
class Context(object):
6463
def __init__(self, testsuite):
6464
self.testsuite = testsuite
6465
6466
def __enter__(self):
6467
self.testsuite.context_push()
6468
6469
def __exit__(self, type, value, traceback):
6470
self.testsuite.context_pop()
6471
return False # re-raise any exception
6472
6473
def sysid_thismav(self):
6474
return 1
6475
6476
def create_MISSION_ITEM_INT(
6477
self,
6478
t,
6479
p1=0,
6480
p2=0,
6481
p3=0,
6482
p4=0,
6483
x=0,
6484
y=0,
6485
z=0,
6486
frame=mavutil.mavlink.MAV_FRAME_GLOBAL,
6487
autocontinue=0,
6488
current=0,
6489
target_system=1,
6490
target_component=1,
6491
seq=0,
6492
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
6493
):
6494
return self.mav.mav.mission_item_int_encode(
6495
target_system,
6496
target_component,
6497
seq, # seq
6498
frame,
6499
t,
6500
current, # current
6501
autocontinue, # autocontinue
6502
p1, # p1
6503
p2, # p2
6504
p3, # p3
6505
p4, # p4
6506
x, # latitude
6507
y, # longitude
6508
z, # altitude
6509
mission_type
6510
)
6511
6512
def run_cmd_int(self,
6513
command,
6514
p1=0,
6515
p2=0,
6516
p3=0,
6517
p4=0,
6518
x=0,
6519
y=0,
6520
z=0,
6521
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
6522
timeout=10,
6523
target_sysid=None,
6524
target_compid=None,
6525
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
6526
p5=None,
6527
p6=None,
6528
p7=None,
6529
quiet=False,
6530
mav=None,
6531
):
6532
6533
if mav is None:
6534
mav = self.mav
6535
6536
if p5 is not None:
6537
x = p5
6538
if p6 is not None:
6539
y = p6
6540
if p7 is not None:
6541
z = p7
6542
6543
if target_sysid is None:
6544
target_sysid = self.sysid_thismav()
6545
if target_compid is None:
6546
target_compid = 1
6547
6548
self.get_sim_time() # required for timeout in run_cmd_get_ack to work
6549
6550
"""Send a MAVLink command int."""
6551
if not quiet:
6552
try:
6553
command_name = mavutil.mavlink.enums["MAV_CMD"][command].name
6554
except KeyError:
6555
command_name = "UNKNOWNu"
6556
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)" % (
6557
target_sysid,
6558
target_compid,
6559
command_name,
6560
command,
6561
p1,
6562
p2,
6563
p3,
6564
p4,
6565
x,
6566
y,
6567
z,
6568
frame
6569
))
6570
mav.mav.command_int_send(target_sysid,
6571
target_compid,
6572
frame,
6573
command,
6574
0, # current
6575
0, # autocontinue
6576
p1,
6577
p2,
6578
p3,
6579
p4,
6580
x,
6581
y,
6582
z)
6583
self.run_cmd_get_ack(command, want_result, timeout, mav=mav)
6584
6585
def send_cmd(self,
6586
command,
6587
p1=0,
6588
p2=0,
6589
p3=0,
6590
p4=0,
6591
p5=0,
6592
p6=0,
6593
p7=0,
6594
target_sysid=None,
6595
target_compid=None,
6596
mav=None,
6597
quiet=False,
6598
):
6599
"""Send a MAVLink command long."""
6600
if mav is None:
6601
mav = self.mav
6602
if target_sysid is None:
6603
target_sysid = self.sysid_thismav()
6604
if target_compid is None:
6605
target_compid = 1
6606
if not quiet:
6607
try:
6608
command_name = mavutil.mavlink.enums["MAV_CMD"][command].name
6609
except KeyError:
6610
command_name = "UNKNOWN"
6611
self.progress("Sending COMMAND_LONG to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" %
6612
(
6613
target_sysid,
6614
target_compid,
6615
command_name,
6616
command,
6617
p1,
6618
p2,
6619
p3,
6620
p4,
6621
p5,
6622
p6,
6623
p7))
6624
mav.mav.command_long_send(target_sysid,
6625
target_compid,
6626
command,
6627
1, # confirmation
6628
p1,
6629
p2,
6630
p3,
6631
p4,
6632
p5,
6633
p6,
6634
p7)
6635
6636
def run_cmd(self,
6637
command,
6638
p1=0,
6639
p2=0,
6640
p3=0,
6641
p4=0,
6642
p5=0,
6643
p6=0,
6644
p7=0,
6645
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
6646
target_sysid=None,
6647
target_compid=None,
6648
timeout=10,
6649
quiet=False,
6650
mav=None):
6651
self.drain_mav(mav=mav)
6652
self.get_sim_time() # required for timeout in run_cmd_get_ack to work
6653
self.send_cmd(
6654
command,
6655
p1,
6656
p2,
6657
p3,
6658
p4,
6659
p5,
6660
p6,
6661
p7,
6662
target_sysid=target_sysid,
6663
target_compid=target_compid,
6664
mav=mav,
6665
quiet=quiet,
6666
)
6667
self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet, mav=mav)
6668
6669
def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, ignore_in_progress=None):
6670
# note that the caller should ensure that this cached
6671
# timestamp is reasonably up-to-date!
6672
if mav is None:
6673
mav = self.mav
6674
if ignore_in_progress is None:
6675
ignore_in_progress = want_result != mavutil.mavlink.MAV_RESULT_IN_PROGRESS
6676
tstart = self.get_sim_time_cached()
6677
while True:
6678
if mav != self.mav:
6679
self.drain_mav()
6680
delta_time = self.get_sim_time_cached() - tstart
6681
if delta_time > timeout:
6682
raise AutoTestTimeoutException("Did not get good COMMAND_ACK within %fs" % timeout)
6683
m = mav.recv_match(type='COMMAND_ACK',
6684
blocking=True,
6685
timeout=0.1)
6686
if m is None:
6687
continue
6688
if not quiet:
6689
self.progress("ACK received: %s (%fs)" % (str(m), delta_time))
6690
if m.command == command:
6691
if m.result == mavutil.mavlink.MAV_RESULT_IN_PROGRESS and ignore_in_progress:
6692
continue
6693
if m.result != want_result:
6694
raise ValueError("Expected %s got %s" % (
6695
mavutil.mavlink.enums["MAV_RESULT"][want_result].name,
6696
mavutil.mavlink.enums["MAV_RESULT"][m.result].name))
6697
break
6698
6699
def set_current_waypoint_using_mav_cmd_do_set_mission_current(
6700
self,
6701
seq,
6702
reset=0,
6703
target_sysid=1,
6704
target_compid=1):
6705
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
6706
p1=seq,
6707
p2=reset,
6708
timeout=1,
6709
target_sysid=target_sysid,
6710
target_compid=target_compid)
6711
6712
def set_current_waypoint_using_mission_set_current(
6713
self,
6714
seq,
6715
target_sysid=1,
6716
target_compid=1,
6717
check_afterwards=True):
6718
self.mav.mav.mission_set_current_send(target_sysid,
6719
target_compid,
6720
seq)
6721
if check_afterwards:
6722
self.wait_current_waypoint(seq, timeout=10)
6723
6724
def set_current_waypoint(self, seq, target_sysid=1, target_compid=1, check_afterwards=True):
6725
return self.set_current_waypoint_using_mission_set_current(
6726
seq,
6727
target_sysid,
6728
target_compid,
6729
check_afterwards=check_afterwards
6730
)
6731
6732
def verify_parameter_values(self, parameter_stuff, max_delta=0.0):
6733
bad = ""
6734
for param in parameter_stuff:
6735
fetched_value = self.get_parameter(param)
6736
wanted_value = parameter_stuff[param]
6737
if isinstance(wanted_value, tuple):
6738
max_delta = wanted_value[1]
6739
wanted_value = wanted_value[0]
6740
if abs(fetched_value - wanted_value) > max_delta:
6741
bad += "%s=%f (want=%f +/-%f) " % (param, fetched_value, wanted_value, max_delta)
6742
if len(bad):
6743
raise NotAchievedException("Bad parameter values: %s" %
6744
(bad,))
6745
6746
#################################################
6747
# UTILITIES
6748
#################################################
6749
def lineno(self):
6750
'''return line number'''
6751
frameinfo = getframeinfo(currentframe().f_back)
6752
# print(frameinfo.filename, frameinfo.lineno)
6753
return frameinfo.lineno
6754
6755
@staticmethod
6756
def longitude_scale(lat):
6757
ret = math.cos(lat * (math.radians(1)))
6758
print("scale=%f" % ret)
6759
return ret
6760
6761
@staticmethod
6762
def get_distance(loc1, loc2):
6763
"""Get ground distance between two locations."""
6764
return TestSuite.get_distance_accurate(loc1, loc2)
6765
# dlat = loc2.lat - loc1.lat
6766
# try:
6767
# dlong = loc2.lng - loc1.lng
6768
# except AttributeError:
6769
# dlong = loc2.lon - loc1.lon
6770
6771
# return math.sqrt((dlat*dlat) + (dlong*dlong)*TestSuite.longitude_scale(loc2.lat)) * 1.113195e5
6772
6773
@staticmethod
6774
def get_distance_accurate(loc1, loc2):
6775
"""Get ground distance between two locations."""
6776
try:
6777
lon1 = loc1.lng
6778
lon2 = loc2.lng
6779
except AttributeError:
6780
lon1 = loc1.lon
6781
lon2 = loc2.lon
6782
6783
return mp_util.gps_distance(loc1.lat, lon1, loc2.lat, lon2)
6784
6785
def assert_distance(self, loc1, loc2, min_distance, max_distance):
6786
dist = self.get_distance_accurate(loc1, loc2)
6787
if dist < min_distance or dist > max_distance:
6788
raise NotAchievedException("Expected distance %f to be between %f and %f" %
6789
(dist, min_distance, max_distance))
6790
self.progress("Distance %f is between %f and %f" %
6791
(dist, min_distance, max_distance))
6792
6793
@staticmethod
6794
def get_latlon_attr(loc, attrs):
6795
'''return any found latitude attribute from loc'''
6796
ret = None
6797
for attr in attrs:
6798
if hasattr(loc, attr):
6799
ret = getattr(loc, attr)
6800
break
6801
if ret is None:
6802
raise ValueError("None of %s in loc(%s)" % (str(attrs), str(loc)))
6803
return ret
6804
6805
@staticmethod
6806
def get_lat_attr(loc):
6807
'''return any found latitude attribute from loc'''
6808
return TestSuite.get_latlon_attr(loc, ["lat", "latitude"])
6809
6810
@staticmethod
6811
def get_lon_attr(loc):
6812
'''return any found latitude attribute from loc'''
6813
return TestSuite.get_latlon_attr(loc, ["lng", "lon", "longitude"])
6814
6815
@staticmethod
6816
def get_distance_int(loc1, loc2):
6817
"""Get ground distance between two locations in the normal "int" form
6818
- lat/lon multiplied by 1e7"""
6819
loc1_lat = TestSuite.get_lat_attr(loc1)
6820
loc2_lat = TestSuite.get_lat_attr(loc2)
6821
loc1_lon = TestSuite.get_lon_attr(loc1)
6822
loc2_lon = TestSuite.get_lon_attr(loc2)
6823
6824
return TestSuite.get_distance_accurate(
6825
mavutil.location(loc1_lat*1e-7, loc1_lon*1e-7),
6826
mavutil.location(loc2_lat*1e-7, loc2_lon*1e-7))
6827
6828
# dlat = loc2_lat - loc1_lat
6829
# dlong = loc2_lon - loc1_lon
6830
#
6831
# dlat /= 10000000.0
6832
# dlong /= 10000000.0
6833
#
6834
# return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e5
6835
6836
def bearing_to(self, loc):
6837
'''return bearing from here to location'''
6838
here = self.mav.location()
6839
return self.get_bearing(here, loc)
6840
6841
@staticmethod
6842
def get_bearing(loc1, loc2):
6843
"""Get bearing from loc1 to loc2."""
6844
off_x = loc2.lng - loc1.lng
6845
off_y = loc2.lat - loc1.lat
6846
bearing = 90.00 + math.atan2(-off_y, off_x) * 57.2957795
6847
if bearing < 0:
6848
bearing += 360.00
6849
return bearing
6850
6851
def send_cmd_do_set_mode(self, mode):
6852
self.send_cmd(
6853
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
6854
p1=mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
6855
p2=self.get_mode_from_mode_mapping(mode),
6856
)
6857
6858
def assert_mode(self, mode):
6859
self.wait_mode(mode, timeout=0)
6860
6861
def change_mode(self, mode, timeout=60):
6862
'''change vehicle flightmode'''
6863
self.wait_heartbeat()
6864
self.progress("Changing mode to %s" % mode)
6865
self.send_cmd_do_set_mode(mode)
6866
tstart = self.get_sim_time()
6867
while not self.mode_is(mode):
6868
custom_num = self.mav.messages['HEARTBEAT'].custom_mode
6869
self.progress("mav.flightmode=%s Want=%s custom=%u" % (
6870
self.mav.flightmode, mode, custom_num))
6871
if (timeout is not None and
6872
self.get_sim_time_cached() > tstart + timeout):
6873
raise WaitModeTimeout("Did not change mode")
6874
self.send_cmd_do_set_mode(mode)
6875
self.progress("Got mode %s" % mode)
6876
6877
def capable(self, capability):
6878
return self.get_autopilot_capabilities() & capability
6879
6880
def assert_capability(self, capability):
6881
if not self.capable(capability):
6882
name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name
6883
raise NotAchievedException("AutoPilot does not have capbility %s" % (name,))
6884
6885
def assert_no_capability(self, capability):
6886
if self.capable(capability):
6887
name = mavutil.mavlink.enums["MAV_PROTOCOL_CAPABILITY"][capability].name
6888
raise NotAchievedException("AutoPilot has feature %s (when it shouln't)" % (name,))
6889
6890
def get_autopilot_capabilities(self):
6891
# Cannot use run_cmd otherwise the respond is lost during the wait for ACK
6892
self.mav.mav.command_long_send(self.sysid_thismav(),
6893
1,
6894
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
6895
0, # confirmation
6896
1, # 1: Request autopilot version
6897
0,
6898
0,
6899
0,
6900
0,
6901
0,
6902
0)
6903
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)
6904
return m.capabilities
6905
6906
def decode_flight_sw_version(self, flight_sw_version: int):
6907
""" Decode 32 bit flight_sw_version mavlink parameter
6908
corresponds to encoding in ardupilot GCS_MAVLINK::send_autopilot_version."""
6909
fw_type_id = (flight_sw_version >> 0) % 256
6910
patch = (flight_sw_version >> 8) % 256
6911
minor = (flight_sw_version >> 16) % 256
6912
major = (flight_sw_version >> 24) % 256
6913
if fw_type_id == 0:
6914
fw_type = "dev"
6915
elif fw_type_id == 64:
6916
fw_type = "alpha"
6917
elif fw_type_id == 128:
6918
fw_type = "beta"
6919
elif fw_type_id == 192:
6920
fw_type = "rc"
6921
elif fw_type_id == 255:
6922
fw_type = "official"
6923
else:
6924
fw_type = "undefined"
6925
return major, minor, patch, fw_type
6926
6927
def get_autopilot_firmware_version(self):
6928
self.mav.mav.command_long_send(self.sysid_thismav(),
6929
1,
6930
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
6931
0, # confirmation
6932
1, # 1: Request autopilot version
6933
0,
6934
0,
6935
0,
6936
0,
6937
0,
6938
0)
6939
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)
6940
self.fcu_firmware_version = self.decode_flight_sw_version(m.flight_sw_version)
6941
6942
def hex_values_to_int(hex_values):
6943
# Convert ascii codes to characters
6944
hex_chars = [chr(int(hex_value)) for hex_value in hex_values]
6945
# Convert hex characters to integers, handle \x00 case
6946
int_values = [0 if hex_char == '\x00' else int(hex_char, 16) for hex_char in hex_chars]
6947
return int_values
6948
6949
fcu_hash_to_hex = ""
6950
for i in hex_values_to_int(m.flight_custom_version):
6951
fcu_hash_to_hex += f"{i:x}"
6952
self.fcu_firmware_hash = fcu_hash_to_hex
6953
self.progress(f"Firmware Version {self.fcu_firmware_version}")
6954
self.progress(f"Firmware hash {self.fcu_firmware_hash}")
6955
self.githash = util.get_git_hash(short=True)
6956
self.progress(f"Git hash {self.githash}")
6957
6958
def GetCapabilities(self):
6959
'''Get Capabilities'''
6960
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT)
6961
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION)
6962
6963
def get_mode_from_mode_mapping(self, mode):
6964
"""Validate and return the mode number from a string or int."""
6965
if isinstance(mode, int):
6966
return mode
6967
mode_map = self.mav.mode_mapping()
6968
if mode_map is None:
6969
mav_type = self.mav.messages['HEARTBEAT'].type
6970
mav_autopilot = self.mav.messages['HEARTBEAT'].autopilot
6971
raise ErrorException("No mode map for (mav_type=%s mav_autopilot=%s)" % (mav_type, mav_autopilot))
6972
if isinstance(mode, str):
6973
if mode in mode_map:
6974
return mode_map.get(mode)
6975
if mode in mode_map.values():
6976
return mode
6977
self.progress("No mode (%s); available modes '%s'" % (mode, mode_map))
6978
raise ErrorException("Unknown mode '%s'" % mode)
6979
6980
def get_mode_string_for_mode(self, mode):
6981
if isinstance(mode, str):
6982
return mode
6983
mode_map = self.mav.mode_mapping()
6984
if mode_map is None:
6985
return f"mode={mode}"
6986
for (n, v) in mode_map.items():
6987
if v == mode:
6988
return n
6989
self.progress(f"No mode ({mode} {type(mode)}); available modes '{mode_map}'")
6990
raise ErrorException("Unknown mode '%s'" % mode)
6991
6992
def run_cmd_do_set_mode(self,
6993
mode,
6994
timeout=30,
6995
run_cmd=None,
6996
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
6997
if run_cmd is None:
6998
run_cmd = self.run_cmd
6999
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
7000
custom_mode = self.get_mode_from_mode_mapping(mode)
7001
run_cmd(
7002
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
7003
p1=base_mode,
7004
p2=custom_mode,
7005
want_result=want_result,
7006
timeout=timeout,
7007
)
7008
7009
def do_set_mode_via_command_XYZZY(self, mode, run_cmd, timeout=30):
7010
"""Set mode with a command long message."""
7011
tstart = self.get_sim_time()
7012
want_custom_mode = self.get_mode_from_mode_mapping(mode)
7013
while True:
7014
remaining = timeout - (self.get_sim_time_cached() - tstart)
7015
if remaining <= 0:
7016
raise AutoTestTimeoutException("Failed to change mode")
7017
self.run_cmd_do_set_mode(mode, run_cmd=run_cmd, timeout=10)
7018
m = self.wait_heartbeat()
7019
self.progress("Got mode=%u want=%u" % (m.custom_mode, want_custom_mode))
7020
if m.custom_mode == want_custom_mode:
7021
return
7022
7023
def do_set_mode_via_command_long(self, mode, timeout=30):
7024
self.do_set_mode_via_command_XYZZY(mode, self.run_cmd, timeout=timeout)
7025
7026
def do_set_mode_via_command_int(self, mode, timeout=30):
7027
self.do_set_mode_via_command_XYZZY(mode, self.run_cmd_int, timeout=timeout)
7028
7029
def mavproxy_do_set_mode_via_command_long(self, mavproxy, mode, timeout=30):
7030
"""Set mode with a command long message with Mavproxy."""
7031
base_mode = mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
7032
custom_mode = self.get_mode_from_mode_mapping(mode)
7033
tstart = self.get_sim_time()
7034
while True:
7035
remaining = timeout - (self.get_sim_time_cached() - tstart)
7036
if remaining <= 0:
7037
raise AutoTestTimeoutException("Failed to change mode")
7038
mavproxy.send("long DO_SET_MODE %u %u\n" %
7039
(base_mode, custom_mode))
7040
m = self.wait_heartbeat()
7041
if m.custom_mode == custom_mode:
7042
return True
7043
7044
def reach_heading_manual(self, heading, turn_right=True):
7045
"""Manually direct the vehicle to the target heading."""
7046
if self.is_copter() or self.is_sub():
7047
self.set_rc(4, 1580)
7048
self.wait_heading(heading)
7049
self.set_rc(4, 1500)
7050
if self.is_plane():
7051
self.set_rc(1, 1800)
7052
self.wait_heading(heading)
7053
self.set_rc(1, 1500)
7054
if self.is_rover():
7055
steering_pwm = 1700
7056
if not turn_right:
7057
steering_pwm = 1300
7058
self.set_rc(1, steering_pwm)
7059
self.set_rc(3, 1550)
7060
self.wait_heading(heading)
7061
self.set_rc(3, 1500)
7062
self.set_rc(1, 1500)
7063
7064
def assert_vehicle_location_is_at_startup_location(self, dist_max=1):
7065
here = self.mav.location()
7066
start_loc = self.sitl_start_location()
7067
dist = self.get_distance(here, start_loc)
7068
data = "dist=%f max=%f (here: %s start-loc: %s)" % (dist, dist_max, here, start_loc)
7069
7070
if dist > dist_max:
7071
raise NotAchievedException("Far from startup location: %s" % data)
7072
self.progress("Close to startup location: %s" % data)
7073
7074
def assert_simstate_location_is_at_startup_location(self, dist_max=1):
7075
simstate_loc = self.sim_location()
7076
start_loc = self.sitl_start_location()
7077
dist = self.get_distance(simstate_loc, start_loc)
7078
data = "dist=%f max=%f (simstate: %s start-loc: %s)" % (dist, dist_max, simstate_loc, start_loc)
7079
7080
if dist > dist_max:
7081
raise NotAchievedException("simstate far from startup location: %s" % data)
7082
self.progress("Simstate Close to startup location: %s" % data)
7083
7084
def reach_distance_manual(self, distance):
7085
"""Manually direct the vehicle to the target distance from home."""
7086
if self.is_copter():
7087
self.set_rc(2, 1350)
7088
self.wait_distance(distance, accuracy=5, timeout=60)
7089
self.set_rc(2, 1500)
7090
if self.is_plane():
7091
self.progress("NOT IMPLEMENTED")
7092
if self.is_rover():
7093
self.set_rc(3, 1700)
7094
self.wait_distance(distance, accuracy=2)
7095
self.set_rc(3, 1500)
7096
7097
def guided_achieve_heading(self, heading, accuracy=None):
7098
tstart = self.get_sim_time()
7099
while True:
7100
if self.get_sim_time_cached() - tstart > 200:
7101
raise NotAchievedException("Did not achieve heading")
7102
self.run_cmd(
7103
mavutil.mavlink.MAV_CMD_CONDITION_YAW,
7104
p1=heading, # target angle
7105
p2=10, # degrees/second
7106
p3=1, # -1 is counter-clockwise, 1 clockwise
7107
p4=0, # 1 for relative, 0 for absolute
7108
)
7109
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
7110
self.progress("heading=%d want=%d" % (m.heading, int(heading)))
7111
if accuracy is not None:
7112
delta = abs(m.heading - int(heading))
7113
if delta <= accuracy:
7114
return
7115
if m.heading == int(heading):
7116
return
7117
7118
def assert_heading(self, heading, accuracy=1):
7119
'''assert vehicle yaw is to heading (0-360)'''
7120
m = self.assert_receive_message('VFR_HUD')
7121
if self.heading_delta(heading, m.heading) > accuracy:
7122
raise NotAchievedException("Unexpected heading=%f want=%f" %
7123
(m.heading, heading))
7124
7125
def do_set_relay(self, relay_num, on_off, timeout=10):
7126
"""Set relay with a command long message."""
7127
self.progress("Set relay %d to %d" % (relay_num, on_off))
7128
self.run_cmd(
7129
mavutil.mavlink.MAV_CMD_DO_SET_RELAY,
7130
p1=relay_num,
7131
p2=on_off,
7132
timeout=timeout,
7133
)
7134
7135
def do_set_relay_mavproxy(self, relay_num, on_off):
7136
"""Set relay with mavproxy."""
7137
self.progress("Set relay %d to %d" % (relay_num, on_off))
7138
self.mavproxy.send('module load relay\n')
7139
self.mavproxy.expect("Loaded module relay")
7140
self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off))
7141
7142
def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7143
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result)
7144
7145
def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7146
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result)
7147
7148
def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7149
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result)
7150
7151
def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
7152
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result)
7153
7154
#################################################
7155
# WAIT UTILITIES
7156
#################################################
7157
def delay_sim_time(self, seconds_to_wait, reason=None):
7158
"""Wait some second in SITL time."""
7159
tstart = self.get_sim_time()
7160
tnow = tstart
7161
r = "Delaying %f seconds"
7162
if reason is not None:
7163
r += " for %s" % reason
7164
self.progress(r % (seconds_to_wait,))
7165
while tstart + seconds_to_wait > tnow:
7166
tnow = self.get_sim_time(drain_mav=False)
7167
7168
def send_terrain_check_message(self):
7169
here = self.mav.location()
7170
self.mav.mav.terrain_check_send(int(here.lat * 1e7), int(here.lng * 1e7))
7171
7172
def get_terrain_height(self, verbose=False):
7173
self.send_terrain_check_message()
7174
m = self.assert_receive_message('TERRAIN_REPORT', very_verbose=True)
7175
return m.terrain_height
7176
7177
def get_altitude(self, relative=False, timeout=30, altitude_source=None):
7178
'''returns vehicles altitude in metres, possibly relative-to-home'''
7179
if altitude_source is None:
7180
if relative:
7181
altitude_source = "GLOBAL_POSITION_INT.relative_alt"
7182
else:
7183
altitude_source = "GLOBAL_POSITION_INT.alt"
7184
if altitude_source == "TERRAIN_REPORT.current_height":
7185
terrain = self.assert_receive_message('TERRAIN_REPORT')
7186
return terrain.current_height
7187
7188
(msg, field) = altitude_source.split('.')
7189
msg = self.poll_message(msg, quiet=True)
7190
divisor = 1000.0 # mm is pretty common in mavlink
7191
if altitude_source == "SIM_STATE.alt":
7192
divisor = 1.0
7193
return getattr(msg, field) / divisor
7194
7195
def assert_altitude(self, alt, accuracy=1, **kwargs):
7196
got_alt = self.get_altitude(**kwargs)
7197
if abs(alt - got_alt) > accuracy:
7198
raise NotAchievedException("Incorrect alt; want=%f got=%f" %
7199
(alt, got_alt))
7200
7201
def assert_rangefinder_distance_between(self, dist_min, dist_max):
7202
m = self.assert_receive_message('RANGEFINDER')
7203
7204
if m.distance < dist_min:
7205
raise NotAchievedException("below min height (%f < %f)" %
7206
(m.distance, dist_min))
7207
7208
if m.distance > dist_max:
7209
raise NotAchievedException("above max height (%f > %f)" %
7210
(m.distance, dist_max))
7211
7212
def assert_distance_sensor_quality(self, quality):
7213
m = self.assert_receive_message('DISTANCE_SENSOR')
7214
7215
if m.signal_quality != quality:
7216
raise NotAchievedException("Unexpected quality; want=%f got=%f" %
7217
(quality, m.signal_quality))
7218
7219
def get_rangefinder_distance(self):
7220
m = self.assert_receive_message('RANGEFINDER', timeout=5)
7221
return m.distance
7222
7223
def wait_rangefinder_distance(self, dist_min, dist_max, timeout=30, **kwargs):
7224
'''wait for RANGEFINDER distance'''
7225
def validator(value2, target2=None):
7226
if dist_min <= value2 <= dist_max:
7227
return True
7228
else:
7229
return False
7230
7231
self.wait_and_maintain(
7232
value_name="RageFinderDistance",
7233
target=dist_min,
7234
current_value_getter=lambda: self.get_rangefinder_distance(),
7235
accuracy=(dist_max - dist_min),
7236
validator=lambda value2, target2: validator(value2, target2),
7237
timeout=timeout,
7238
**kwargs
7239
)
7240
7241
def get_esc_rpm(self, esc):
7242
if esc > 4:
7243
raise ValueError("Only does 1-4")
7244
m = self.assert_receive_message('ESC_TELEMETRY_1_TO_4', timeout=1, verbose=True)
7245
return m.rpm[esc-1]
7246
7247
def find_first_set_bit(self, mask):
7248
'''returns offset of first-set-bit (counting from right) in mask. Returns None if no bits set'''
7249
pos = 0
7250
while mask != 0:
7251
if mask & 0x1:
7252
return pos
7253
mask = mask >> 1
7254
pos += 1
7255
return None
7256
7257
def get_rpm(self, rpm_sensor):
7258
m = self.assert_receive_message('RPM')
7259
if rpm_sensor == 1:
7260
ret = m.rpm1
7261
elif rpm_sensor == 2:
7262
ret = m.rpm2
7263
else:
7264
raise ValueError("Bad sensor id")
7265
if ret < 0.000001:
7266
# yay filtering!
7267
return 0
7268
return ret
7269
7270
def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs):
7271
'''wait for RPM to be between rpm_min and rpm_max'''
7272
def validator(value2, target2=None):
7273
return rpm_min <= value2 <= rpm_max
7274
self.wait_and_maintain(
7275
value_name="RPM%u" % rpm_sensor,
7276
target=(rpm_min+rpm_max)/2.0,
7277
current_value_getter=lambda: self.get_rpm(rpm_sensor),
7278
accuracy=rpm_max-rpm_min,
7279
validator=lambda value2, target2: validator(value2, target2),
7280
**kwargs
7281
)
7282
7283
def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs):
7284
'''wait for ESC to be between rpm_min and rpm_max'''
7285
def validator(value2, target2=None):
7286
return rpm_min <= value2 <= rpm_max
7287
self.wait_and_maintain(
7288
value_name="ESC %u RPM" % esc,
7289
target=(rpm_min+rpm_max)/2.0,
7290
current_value_getter=lambda: self.get_esc_rpm(esc),
7291
accuracy=rpm_max-rpm_min,
7292
validator=lambda value2, target2: validator(value2, target2),
7293
**kwargs
7294
)
7295
7296
def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=None, **kwargs):
7297
"""Wait for a given altitude range."""
7298
assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude."
7299
7300
if timeout is None:
7301
timeout = 30
7302
7303
def validator(value2, target2=None):
7304
if altitude_min <= value2 <= altitude_max:
7305
return True
7306
else:
7307
return False
7308
7309
altitude_source = kwargs.get("altitude_source", None)
7310
7311
self.wait_and_maintain(
7312
value_name="Altitude",
7313
target=(altitude_min + altitude_max)*0.5,
7314
current_value_getter=lambda: self.get_altitude(
7315
relative=relative,
7316
timeout=timeout,
7317
altitude_source=altitude_source,
7318
),
7319
accuracy=(altitude_max - altitude_min)*0.5,
7320
validator=lambda value2, target2: validator(value2, target2),
7321
timeout=timeout,
7322
**kwargs
7323
)
7324
7325
def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True, altitude_source=None):
7326
"""Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration"""
7327
return self.wait_altitude(
7328
altitude_min=altitude_min,
7329
altitude_max=altitude_max,
7330
relative=relative,
7331
minimum_duration=minimum_duration,
7332
timeout=minimum_duration + 1,
7333
altitude_source=altitude_source,
7334
)
7335
7336
def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs):
7337
"""Wait for a given vertical rate."""
7338
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
7339
7340
def get_climbrate(timeout2):
7341
msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)
7342
return msg.climb
7343
7344
def validator(value2, target2=None):
7345
if speed_min <= value2 <= speed_max:
7346
return True
7347
else:
7348
return False
7349
7350
self.wait_and_maintain(
7351
value_name="Climbrate",
7352
target=speed_min,
7353
current_value_getter=lambda: get_climbrate(timeout),
7354
accuracy=(speed_max - speed_min),
7355
validator=lambda value2, target2: validator(value2, target2),
7356
timeout=timeout,
7357
**kwargs
7358
)
7359
7360
def groundspeed(self):
7361
m = self.assert_receive_message('VFR_HUD')
7362
return m.groundspeed
7363
7364
def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs):
7365
self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs)
7366
7367
def wait_airspeed(self, speed_min, speed_max, timeout=30, **kwargs):
7368
self.wait_vfr_hud_speed("airspeed", speed_min, speed_max, timeout=timeout, **kwargs)
7369
7370
def wait_vfr_hud_speed(self, field, speed_min, speed_max, timeout=30, **kwargs):
7371
"""Wait for a given ground speed range."""
7372
assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."
7373
7374
def get_speed(timeout2):
7375
msg = self.assert_receive_message('VFR_HUD', timeout=timeout2)
7376
return getattr(msg, field)
7377
7378
self.wait_and_maintain_range(
7379
value_name=field,
7380
minimum=speed_min,
7381
maximum=speed_max,
7382
current_value_getter=lambda: get_speed(timeout),
7383
validator=None,
7384
timeout=timeout,
7385
**kwargs
7386
)
7387
7388
def wait_roll(self, roll, accuracy, timeout=30, **kwargs):
7389
"""Wait for a given roll in degrees."""
7390
def get_roll(timeout2):
7391
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7392
p = math.degrees(msg.pitch)
7393
r = math.degrees(msg.roll)
7394
self.progress("Roll %d Pitch %d" % (r, p))
7395
return r
7396
7397
def validator(value2, target2):
7398
return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy
7399
7400
self.wait_and_maintain(
7401
value_name="Roll",
7402
target=roll,
7403
current_value_getter=lambda: get_roll(timeout),
7404
validator=lambda value2, target2: validator(value2, target2),
7405
accuracy=accuracy,
7406
timeout=timeout,
7407
**kwargs
7408
)
7409
7410
def wait_pitch(self, pitch, accuracy, timeout=30, **kwargs):
7411
"""Wait for a given pitch in degrees."""
7412
def get_pitch(timeout2):
7413
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7414
p = math.degrees(msg.pitch)
7415
r = math.degrees(msg.roll)
7416
self.progress("Pitch %d Roll %d" % (p, r))
7417
return p
7418
7419
def validator(value2, target2):
7420
return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy
7421
7422
self.wait_and_maintain(
7423
value_name="Pitch",
7424
target=pitch,
7425
current_value_getter=lambda: get_pitch(timeout),
7426
validator=lambda value2, target2: validator(value2, target2),
7427
accuracy=accuracy,
7428
timeout=timeout,
7429
**kwargs
7430
)
7431
7432
def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs):
7433
if isinstance(target, Vector3):
7434
return self.wait_and_maintain_vector(
7435
value_name,
7436
target,
7437
current_value_getter,
7438
validator,
7439
timeout=30,
7440
**kwargs
7441
)
7442
return self.wait_and_maintain_range(
7443
value_name,
7444
minimum=target - accuracy,
7445
maximum=target + accuracy,
7446
current_value_getter=current_value_getter,
7447
validator=validator,
7448
timeout=timeout,
7449
print_diagnostics_as_target_not_range=True,
7450
**kwargs
7451
)
7452
7453
def wait_and_maintain_vector(self,
7454
value_name,
7455
target,
7456
current_value_getter,
7457
validator,
7458
timeout=30,
7459
**kwargs):
7460
tstart = self.get_sim_time()
7461
achieving_duration_start = None
7462
sum_of_achieved_values = Vector3()
7463
last_value = Vector3()
7464
last_fail_print = 0
7465
count_of_achieved_values = 0
7466
called_function = kwargs.get("called_function", None)
7467
minimum_duration = kwargs.get("minimum_duration", 0)
7468
if minimum_duration >= timeout:
7469
raise ValueError("minimum_duration >= timeout")
7470
7471
self.progress("Waiting for %s=(%s)" % (value_name, str(target)))
7472
7473
last_print_time = 0
7474
while True: # if we failed to received message with the getter the sim time isn't updated # noqa
7475
now = self.get_sim_time_cached()
7476
if now - tstart > timeout:
7477
raise AutoTestTimeoutException(
7478
"Failed to attain %s want %s, reached %s" %
7479
(value_name,
7480
str(target),
7481
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) # noqa
7482
7483
last_value = current_value_getter()
7484
if called_function is not None:
7485
called_function(last_value, target)
7486
is_value_valid = validator(last_value, target)
7487
if self.get_sim_time_cached() - last_print_time > 1:
7488
if is_value_valid:
7489
want_or_got = "got"
7490
else:
7491
want_or_got = "want"
7492
achieved_duration_bit = ""
7493
if achieving_duration_start is not None:
7494
so_far = self.get_sim_time_cached() - achieving_duration_start
7495
achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)
7496
self.progress(
7497
"%s=(%s) (%s (%s))%s" %
7498
(value_name,
7499
str(last_value),
7500
want_or_got,
7501
str(target),
7502
achieved_duration_bit)
7503
)
7504
last_print_time = self.get_sim_time_cached()
7505
if is_value_valid:
7506
sum_of_achieved_values += last_value
7507
count_of_achieved_values += 1.0
7508
if achieving_duration_start is None:
7509
achieving_duration_start = self.get_sim_time_cached()
7510
if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:
7511
self.progress("Attained %s=%s" % (
7512
value_name,
7513
str(sum_of_achieved_values * (1.0 / count_of_achieved_values))))
7514
return True
7515
else:
7516
achieving_duration_start = None
7517
sum_of_achieved_values.zero()
7518
count_of_achieved_values = 0
7519
if now - last_fail_print > 1:
7520
self.progress("Waiting for (%s), got %s" %
7521
(target, last_value))
7522
last_fail_print = now
7523
7524
def validate_kwargs(self, kwargs, valid={}):
7525
for key in kwargs:
7526
if key not in valid:
7527
raise NotAchievedException("Invalid kwarg %s" % str(key))
7528
7529
def wait_and_maintain_range(self,
7530
value_name,
7531
minimum,
7532
maximum,
7533
current_value_getter,
7534
validator=None,
7535
value_averager=None,
7536
timeout=30,
7537
print_diagnostics_as_target_not_range=False,
7538
**kwargs):
7539
self.validate_kwargs(kwargs, valid=frozenset([
7540
"called_function",
7541
"minimum_duration",
7542
"altitude_source",
7543
]))
7544
7545
if print_diagnostics_as_target_not_range:
7546
target = (minimum + maximum) / 2
7547
accuracy = (maximum - minimum) / 2
7548
tstart = self.get_sim_time()
7549
achieving_duration_start = None
7550
sum_of_achieved_values = 0.0
7551
last_value = 0.0
7552
count_of_achieved_values = 0
7553
called_function = kwargs.get("called_function", None)
7554
minimum_duration = kwargs.get("minimum_duration", 0)
7555
if minimum_duration >= timeout:
7556
raise ValueError("minimum_duration >= timeout")
7557
if print_diagnostics_as_target_not_range:
7558
self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy))
7559
else:
7560
self.progress("Waiting for %s between (%s) and (%s)" % (value_name, str(minimum), str(maximum)))
7561
last_print_time = 0
7562
while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa
7563
last_value = current_value_getter()
7564
if called_function is not None:
7565
if print_diagnostics_as_target_not_range:
7566
called_function(last_value, target)
7567
else:
7568
called_function(last_value, minimum, maximum)
7569
if validator is not None:
7570
if print_diagnostics_as_target_not_range:
7571
is_value_valid = validator(last_value, target)
7572
else:
7573
is_value_valid = validator(last_value, minimum, maximum)
7574
else:
7575
is_value_valid = (minimum <= last_value) and (last_value <= maximum)
7576
if self.get_sim_time_cached() - last_print_time > 1:
7577
if is_value_valid:
7578
want_or_got = "got"
7579
else:
7580
want_or_got = "want"
7581
achieved_duration_bit = ""
7582
if achieving_duration_start is not None:
7583
so_far = self.get_sim_time_cached() - achieving_duration_start
7584
achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration)
7585
7586
if print_diagnostics_as_target_not_range:
7587
self.progress(
7588
"%s=%0.2f (%s %f +- %f)%s" %
7589
(value_name,
7590
last_value,
7591
want_or_got,
7592
target,
7593
accuracy,
7594
achieved_duration_bit)
7595
)
7596
else:
7597
if isinstance(last_value, float):
7598
self.progress(
7599
"%s=%0.2f (%s between %s and %s)%s" %
7600
(value_name,
7601
last_value,
7602
want_or_got,
7603
str(minimum),
7604
str(maximum),
7605
achieved_duration_bit)
7606
)
7607
else:
7608
self.progress(
7609
"%s=%s (%s between %s and %s)%s" %
7610
(value_name,
7611
last_value,
7612
want_or_got,
7613
str(minimum),
7614
str(maximum),
7615
achieved_duration_bit)
7616
)
7617
last_print_time = self.get_sim_time_cached()
7618
if is_value_valid:
7619
if value_averager is not None:
7620
average = value_averager.add_value(last_value)
7621
else:
7622
sum_of_achieved_values += last_value
7623
count_of_achieved_values += 1.0
7624
average = sum_of_achieved_values / count_of_achieved_values
7625
if achieving_duration_start is None:
7626
achieving_duration_start = self.get_sim_time_cached()
7627
if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration:
7628
self.progress("Attained %s=%s" % (value_name, average))
7629
return True
7630
else:
7631
achieving_duration_start = None
7632
sum_of_achieved_values = 0.0
7633
count_of_achieved_values = 0
7634
if value_averager is not None:
7635
value_averager.reset()
7636
if print_diagnostics_as_target_not_range:
7637
raise AutoTestTimeoutException(
7638
"Failed to attain %s want %s, reached %s" %
7639
(value_name,
7640
str(target),
7641
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))
7642
else:
7643
raise AutoTestTimeoutException(
7644
"Failed to attain %s between %s and %s, reached %s" %
7645
(value_name,
7646
str(minimum),
7647
str(maximum),
7648
str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value)))
7649
7650
def heading_delta(self, heading1, heading2):
7651
'''return angle between two 0-360 headings'''
7652
return math.fabs((heading1 - heading2 + 180) % 360 - 180)
7653
7654
def get_heading(self, timeout=1):
7655
'''return heading 0-359'''
7656
m = self.assert_receive_message('VFR_HUD', timeout=timeout)
7657
return m.heading
7658
7659
def wait_heading(self, heading, accuracy=5, timeout=30, **kwargs):
7660
"""Wait for a given heading."""
7661
def get_heading_wrapped(timeout2):
7662
return self.get_heading(timeout=timeout2)
7663
7664
def validator(value2, target2):
7665
return self.heading_delta(value2, target2) <= accuracy
7666
7667
self.wait_and_maintain(
7668
value_name="Heading",
7669
target=heading,
7670
current_value_getter=lambda: get_heading_wrapped(timeout),
7671
validator=lambda value2, target2: validator(value2, target2),
7672
accuracy=accuracy,
7673
timeout=timeout,
7674
**kwargs
7675
)
7676
7677
def wait_yaw_speed(self, yaw_speed, accuracy=0.1, timeout=30, **kwargs):
7678
"""Wait for a given yaw speed in radians per second."""
7679
def get_yawspeed(timeout2):
7680
msg = self.assert_receive_message('ATTITUDE', timeout=timeout2)
7681
return msg.yawspeed
7682
7683
def validator(value2, target2):
7684
return math.fabs(value2 - target2) <= accuracy
7685
7686
self.wait_and_maintain(
7687
value_name="YawSpeed",
7688
target=yaw_speed,
7689
current_value_getter=lambda: get_yawspeed(timeout),
7690
validator=lambda value2, target2: validator(value2, target2),
7691
accuracy=accuracy,
7692
timeout=timeout,
7693
**kwargs
7694
)
7695
7696
def get_speed_vector(self, timeout=1):
7697
'''return speed vector, NED'''
7698
msg = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)
7699
return Vector3(msg.vx, msg.vy, msg.vz)
7700
7701
"""Wait for a given speed vector."""
7702
def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs):
7703
def validator(value2, target2):
7704
for (want, got) in (target2.x, value2.x), (target2.y, value2.y), (target2.z, value2.z):
7705
if want != float("nan") and (math.fabs(got - want) > accuracy):
7706
return False
7707
return True
7708
7709
self.wait_and_maintain(
7710
value_name="SpeedVector",
7711
target=speed_vector,
7712
current_value_getter=lambda: self.get_speed_vector(timeout=timeout),
7713
validator=lambda value2, target2: validator(value2, target2),
7714
accuracy=accuracy,
7715
timeout=timeout,
7716
**kwargs
7717
)
7718
7719
def get_descent_rate(self):
7720
'''get descent rate - a positive number if you are going down'''
7721
return abs(self.get_speed_vector().z)
7722
7723
def wait_descent_rate(self, rate, accuracy=0.1, **kwargs):
7724
'''wait for descent rate rate, a positive number if going down'''
7725
def validator(value, target):
7726
return math.fabs(value - target) <= accuracy
7727
7728
self.wait_and_maintain(
7729
value_name="DescentRate",
7730
target=rate,
7731
current_value_getter=lambda: self.get_descent_rate(),
7732
validator=lambda value, target: validator(value, target),
7733
accuracy=accuracy,
7734
**kwargs
7735
)
7736
7737
def get_body_frame_velocity(self):
7738
gri = self.assert_receive_message('GPS_RAW_INT', timeout=1)
7739
att = self.assert_receive_message('ATTITUDE', timeout=1)
7740
return mavextra.gps_velocity_body(gri, att)
7741
7742
def wait_speed_vector_bf(self, speed_vector, accuracy=0.2, timeout=30, **kwargs):
7743
"""Wait for a given speed vector."""
7744
def get_speed_vector(timeout2):
7745
return self.get_body_frame_velocity()
7746
7747
def validator(value2, target2):
7748
return (math.fabs(value2.x - target2.x) <= accuracy and
7749
math.fabs(value2.y - target2.y) <= accuracy and
7750
math.fabs(value2.z - target2.z) <= accuracy)
7751
7752
self.wait_and_maintain(
7753
value_name="SpeedVectorBF",
7754
target=speed_vector,
7755
current_value_getter=lambda: get_speed_vector(timeout),
7756
validator=lambda value2, target2: validator(value2, target2),
7757
accuracy=accuracy,
7758
timeout=timeout,
7759
**kwargs
7760
)
7761
7762
def wait_distance_between(self, series1, series2, min_distance, max_distance, timeout=30, **kwargs):
7763
"""Wait for distance between two position series to be between two thresholds."""
7764
def get_distance():
7765
self.drain_mav()
7766
m1 = self.mav.messages[series1]
7767
m2 = self.mav.messages[series2]
7768
return self.get_distance_int(m1, m2)
7769
7770
self.wait_and_maintain_range(
7771
value_name=f"Distance({series1}, {series2})",
7772
minimum=min_distance,
7773
maximum=max_distance,
7774
current_value_getter=lambda: get_distance(),
7775
timeout=timeout,
7776
**kwargs
7777
)
7778
7779
def wait_distance(self, distance, accuracy=2, timeout=30, **kwargs):
7780
"""Wait for flight of a given distance."""
7781
start = self.mav.location()
7782
7783
def get_distance():
7784
return self.get_distance(start, self.mav.location())
7785
7786
def validator(value2, target2):
7787
return math.fabs(value2 - target2) <= accuracy
7788
7789
self.wait_and_maintain(
7790
value_name="Distance",
7791
target=distance,
7792
current_value_getter=lambda: get_distance(),
7793
validator=lambda value2, target2: validator(value2, target2),
7794
accuracy=accuracy,
7795
timeout=timeout,
7796
**kwargs
7797
)
7798
7799
def wait_distance_to_waypoint(self, wp_num, distance_min, distance_max, **kwargs):
7800
# TODO: use mission_request_partial_list_send
7801
wps = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
7802
m = wps[wp_num]
7803
self.progress("m: %s" % str(m))
7804
loc = mavutil.location(m.x / 1.0e7, m.y / 1.0e7, 0, 0)
7805
self.progress("loc: %s" % str(loc))
7806
self.wait_distance_to_location(loc, distance_min, distance_max, **kwargs)
7807
7808
def wait_distance_to_location(self, location, distance_min, distance_max, timeout=30, **kwargs):
7809
"""Wait for flight of a given distance."""
7810
assert distance_min <= distance_max, "Distance min should be less than distance max."
7811
7812
def get_distance():
7813
return self.get_distance(location, self.mav.location())
7814
7815
def validator(value2, target2=None):
7816
return distance_min <= value2 <= distance_max
7817
7818
self.wait_and_maintain(
7819
value_name="Distance",
7820
target=distance_min,
7821
current_value_getter=lambda: get_distance(),
7822
validator=lambda value2, target2: validator(value2, target2),
7823
accuracy=(distance_max - distance_min), timeout=timeout,
7824
**kwargs
7825
)
7826
7827
def wait_distance_to_home(self, distance_min, distance_max, timeout=10, use_cached_home=True, **kwargs):
7828
"""Wait for distance to home to be within specified bounds."""
7829
assert distance_min <= distance_max, "Distance min should be less than distance max."
7830
7831
def get_distance():
7832
return self.distance_to_home(use_cached_home)
7833
7834
def validator(value2, target2=None):
7835
return distance_min <= value2 <= distance_max
7836
7837
self.wait_and_maintain(
7838
value_name="Distance to home",
7839
target=distance_min,
7840
current_value_getter=lambda: get_distance(),
7841
validator=lambda value2, target2: validator(value2, target2),
7842
accuracy=(distance_max - distance_min), timeout=timeout,
7843
**kwargs
7844
)
7845
7846
def assert_at_home(self, accuracy=1):
7847
if self.distance_to_home() > accuracy:
7848
raise NotAchievedException("Not at home")
7849
7850
def wait_distance_to_nav_target(self,
7851
distance_min,
7852
distance_max,
7853
timeout=10,
7854
use_cached_nav_controller_output=False,
7855
**kwargs):
7856
"""Wait for distance to home to be within specified bounds."""
7857
assert distance_min <= distance_max, "Distance min should be less than distance max."
7858
7859
def get_distance():
7860
return self.distance_to_nav_target(use_cached_nav_controller_output)
7861
7862
def validator(value2, target2=None):
7863
return distance_min <= value2 <= distance_max
7864
7865
self.wait_and_maintain(
7866
value_name="Distance to nav target",
7867
target=distance_min,
7868
current_value_getter=lambda: get_distance(),
7869
validator=lambda value2,
7870
target2: validator(value2, target2),
7871
accuracy=(distance_max - distance_min),
7872
timeout=timeout,
7873
**kwargs
7874
)
7875
7876
def distance_to_local_position(self, local_pos, timeout=30):
7877
(x, y, z_down) = local_pos # alt is *up*
7878
7879
pos = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout)
7880
7881
delta_x = pos.x - x
7882
delta_y = pos.y - y
7883
delta_z = pos.z - z_down
7884
return math.sqrt(delta_x*delta_x + delta_y*delta_y + delta_z*delta_z)
7885
7886
def wait_distance_to_local_position(self,
7887
local_position, # (x, y, z_down)
7888
distance_min,
7889
distance_max,
7890
timeout=10,
7891
**kwargs):
7892
"""Wait for distance to home to be within specified bounds."""
7893
assert distance_min <= distance_max, "Distance min should be less than distance max."
7894
7895
def get_distance():
7896
return self.distance_to_local_position(local_position)
7897
7898
def validator(value2, target2=None):
7899
return distance_min <= value2 <= distance_max
7900
7901
(x, y, z_down) = local_position
7902
self.wait_and_maintain(
7903
value_name="Distance to (%f,%f,%f)" % (x, y, z_down),
7904
target=distance_min,
7905
current_value_getter=lambda: get_distance(),
7906
validator=lambda value2,
7907
target2: validator(value2, target2),
7908
accuracy=(distance_max - distance_min),
7909
timeout=timeout,
7910
**kwargs
7911
)
7912
7913
def wait_parameter_value(self, parameter, value, timeout=10):
7914
tstart = self.get_sim_time()
7915
while True:
7916
if self.get_sim_time_cached() - tstart > timeout:
7917
raise NotAchievedException("%s never got value %f" %
7918
(parameter, value))
7919
v = self.get_parameter(parameter, verbose=False)
7920
self.progress("Got parameter value (%s=%f)" %
7921
(parameter, v))
7922
if v == value:
7923
return
7924
self.delay_sim_time(0.1)
7925
7926
def get_servo_channel_value(self, channel, timeout=2):
7927
channel_field = "servo%u_raw" % channel
7928
tstart = self.get_sim_time()
7929
while True:
7930
remaining = timeout - (self.get_sim_time_cached() - tstart)
7931
if remaining <= 0:
7932
raise NotAchievedException("Channel value condition not met")
7933
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
7934
blocking=True,
7935
timeout=remaining)
7936
if m is None:
7937
continue
7938
m_value = getattr(m, channel_field, None)
7939
if m_value is None:
7940
raise ValueError("message (%s) has no field %s" %
7941
(str(m), channel_field))
7942
return m_value
7943
7944
def wait_servo_channel_value(self, channel, value, epsilon=0, timeout=2, comparator=operator.eq):
7945
"""wait for channel value comparison (default condition is equality)"""
7946
channel_field = "servo%u_raw" % channel
7947
opstring = ("%s" % comparator)[-3:-1]
7948
tstart = self.get_sim_time()
7949
while True:
7950
remaining = timeout - (self.get_sim_time_cached() - tstart)
7951
if remaining <= 0:
7952
raise NotAchievedException("Channel value condition not met")
7953
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
7954
blocking=True,
7955
timeout=remaining)
7956
if m is None:
7957
continue
7958
m_value = getattr(m, channel_field, None)
7959
if m_value is None:
7960
raise ValueError("message (%s) has no field %s" %
7961
(str(m), channel_field))
7962
self.progress("SERVO_OUTPUT_RAW.%s got=%u %s want=%u" %
7963
(channel_field, m_value, opstring, value))
7964
if comparator == operator.eq:
7965
if abs(m_value - value) <= epsilon:
7966
return m_value
7967
if comparator(m_value, value):
7968
return m_value
7969
7970
def wait_servo_channel_in_range(self, channel, v_min, v_max, timeout=2):
7971
"""wait for channel value to be within acceptable range"""
7972
channel_field = "servo%u_raw" % channel
7973
tstart = self.get_sim_time()
7974
while True:
7975
remaining = timeout - (self.get_sim_time_cached() - tstart)
7976
if remaining <= 0:
7977
raise NotAchievedException("Channel value condition not met")
7978
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
7979
blocking=True,
7980
timeout=remaining)
7981
if m is None:
7982
continue
7983
m_value = getattr(m, channel_field, None)
7984
if m_value is None:
7985
raise ValueError("message (%s) has no field %s" %
7986
(str(m), channel_field))
7987
self.progress("want %u <= SERVO_OUTPUT_RAW.%s <= %u, got value = %u" %
7988
(v_min, channel_field, v_max, m_value))
7989
if (v_min <= m_value) and (m_value <= v_max):
7990
return m_value
7991
7992
def assert_servo_channel_value(self, channel, value, comparator=operator.eq):
7993
"""assert channel value (default condition is equality)"""
7994
channel_field = "servo%u_raw" % channel
7995
opstring = ("%s" % comparator)[-3:-1]
7996
m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)
7997
m_value = getattr(m, channel_field, None)
7998
if m_value is None:
7999
raise ValueError("message (%s) has no field %s" %
8000
(str(m), channel_field))
8001
self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" %
8002
(channel_field, m_value, opstring, value))
8003
if comparator(m_value, value):
8004
return m_value
8005
raise NotAchievedException("Wrong value")
8006
8007
def assert_servo_channel_range(self, channel, value_min, value_max):
8008
"""assert channel value is within the range [value_min, value_max]"""
8009
channel_field = "servo%u_raw" % channel
8010
m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1)
8011
m_value = getattr(m, channel_field, None)
8012
if m_value is None:
8013
raise ValueError("message (%s) has no field %s" %
8014
(str(m), channel_field))
8015
self.progress("assert SERVO_OUTPUT_RAW.%s=%u in [%u, %u]" %
8016
(channel_field, m_value, value_min, value_max))
8017
if m_value >= value_min and m_value <= value_max:
8018
return m_value
8019
raise NotAchievedException("Wrong value")
8020
8021
def get_rc_channel_value(self, channel, timeout=2):
8022
"""wait for channel to hit value"""
8023
channel_field = "chan%u_raw" % channel
8024
tstart = self.get_sim_time()
8025
while True:
8026
remaining = timeout - (self.get_sim_time_cached() - tstart)
8027
if remaining <= 0:
8028
raise NotAchievedException("Channel never achieved value")
8029
m = self.mav.recv_match(type='RC_CHANNELS',
8030
blocking=True,
8031
timeout=remaining)
8032
if m is None:
8033
continue
8034
m_value = getattr(m, channel_field)
8035
if m_value is None:
8036
raise ValueError("message (%s) has no field %s" %
8037
(str(m), channel_field))
8038
return m_value
8039
8040
def wait_rc_channel_value(self, channel, value, timeout=2):
8041
channel_field = "chan%u_raw" % channel
8042
tstart = self.get_sim_time()
8043
while True:
8044
remaining = timeout - (self.get_sim_time_cached() - tstart)
8045
if remaining <= 0:
8046
raise NotAchievedException("Channel never achieved value")
8047
m_value = self.get_rc_channel_value(channel, timeout=timeout)
8048
self.progress("RC_CHANNELS.%s=%u want=%u" %
8049
(channel_field, m_value, value))
8050
if value == m_value:
8051
return
8052
8053
def assert_rc_channel_value(self, channel, value):
8054
channel_field = "chan%u_raw" % channel
8055
8056
m_value = self.get_rc_channel_value(channel, timeout=1)
8057
self.progress("RC_CHANNELS.%s=%u want=%u" %
8058
(channel_field, m_value, value))
8059
if value != m_value:
8060
raise NotAchievedException("Expected %s to be %u got %u" %
8061
(channel, value, m_value))
8062
8063
def send_do_reposition(self,
8064
loc,
8065
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT):
8066
'''send a DO_REPOSITION command for a location'''
8067
self.run_cmd_int(
8068
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
8069
0,
8070
0,
8071
0,
8072
0,
8073
int(loc.lat*1e7), # lat* 1e7
8074
int(loc.lng*1e7), # lon* 1e7
8075
loc.alt,
8076
frame=frame
8077
)
8078
8079
def add_rally_point(self, loc, seq, total):
8080
'''add a rally point at the given location'''
8081
self.mav.mav.rally_point_send(1, # target system
8082
0, # target component
8083
seq, # sequence number
8084
total, # total count
8085
int(loc.lat * 1e7),
8086
int(loc.lng * 1e7),
8087
loc.alt, # relative alt
8088
0, # "break" alt?!
8089
0, # "land dir"
8090
0) # flags
8091
8092
def wait_location(self, loc, **kwargs):
8093
waiter = WaitAndMaintainLocation(self, loc, **kwargs)
8094
waiter.run()
8095
8096
def assert_current_waypoint(self, wpnum):
8097
seq = self.mav.waypoint_current()
8098
if seq != wpnum:
8099
raise NotAchievedException("Incorrect current wp")
8100
8101
def wait_current_waypoint(self, wpnum, timeout=70):
8102
tstart = self.get_sim_time()
8103
while True:
8104
if self.get_sim_time() - tstart > timeout:
8105
raise AutoTestTimeoutException("Did not get wanted current waypoint")
8106
seq = self.mav.waypoint_current()
8107
wp_dist = None
8108
try:
8109
wp_dist = self.mav.messages['NAV_CONTROLLER_OUTPUT'].wp_dist
8110
except (KeyError, AttributeError):
8111
pass
8112
self.progress("Waiting for wp=%u current=%u dist=%sm" % (wpnum, seq, wp_dist))
8113
if seq == wpnum:
8114
break
8115
8116
def wait_waypoint(self,
8117
wpnum_start,
8118
wpnum_end,
8119
allow_skip=True,
8120
max_dist=2,
8121
timeout=400,
8122
ignore_RTL_mode_change=False):
8123
"""Wait for waypoint ranges."""
8124
tstart = self.get_sim_time()
8125
# this message arrives after we set the current WP
8126
start_wp = self.mav.waypoint_current()
8127
current_wp = start_wp
8128
mode = self.mav.flightmode
8129
8130
self.progress("wait for waypoint ranges start=%u end=%u"
8131
% (wpnum_start, wpnum_end))
8132
# if start_wp != wpnum_start:
8133
# raise WaitWaypointTimeout("test: Expected start waypoint %u "
8134
# "but got %u" %
8135
# (wpnum_start, start_wp))
8136
8137
last_wp_msg = 0
8138
while self.get_sim_time_cached() < tstart + timeout:
8139
seq = self.mav.waypoint_current()
8140
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT')
8141
wp_dist = m.wp_dist
8142
m = self.assert_receive_message('VFR_HUD')
8143
8144
# if we changed mode, fail
8145
if not self.mode_is('AUTO'):
8146
self.progress(f"{self.mav.flightmode} vs {self.get_mode_from_mode_mapping(mode)}")
8147
if not ignore_RTL_mode_change or not self.mode_is('RTL', cached=True):
8148
new_mode_str = self.get_mode_string_for_mode(self.get_mode())
8149
raise WaitWaypointTimeout(f'Exited {mode} mode to {new_mode_str} ignore={ignore_RTL_mode_change}')
8150
8151
if self.get_sim_time_cached() - last_wp_msg > 1:
8152
self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u,"
8153
"wpnum_end: %u" %
8154
(seq, wp_dist, m.alt, current_wp, wpnum_end))
8155
last_wp_msg = self.get_sim_time_cached()
8156
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
8157
self.progress("WW: Starting new waypoint %u" % seq)
8158
tstart = self.get_sim_time()
8159
current_wp = seq
8160
# the wp_dist check is a hack until we can sort out
8161
# the right seqnum for end of mission
8162
# if current_wp == wpnum_end or (current_wp == wpnum_end-1 and
8163
# wp_dist < 2):
8164
if current_wp == wpnum_end and wp_dist < max_dist:
8165
self.progress("Reached final waypoint %u" % seq)
8166
return True
8167
if seq >= 255:
8168
self.progress("Reached final waypoint %u" % seq)
8169
return True
8170
if seq > current_wp+1:
8171
raise WaitWaypointTimeout(("Skipped waypoint! Got wp %u expected %u"
8172
% (seq, current_wp+1)))
8173
raise WaitWaypointTimeout("Timed out waiting for waypoint %u of %u" %
8174
(wpnum_end, wpnum_end))
8175
8176
def get_cached_message(self, message_type):
8177
'''returns the most-recently received instance of message_type'''
8178
return self.mav.messages[message_type]
8179
8180
def mode_is(self, mode, cached=False, drain_mav=True, drain_mav_quietly=True):
8181
if not cached:
8182
self.wait_heartbeat(drain_mav=drain_mav, quiet=drain_mav_quietly)
8183
try:
8184
return self.get_mode_from_mode_mapping(self.mav.flightmode) == self.get_mode_from_mode_mapping(mode)
8185
except Exception:
8186
pass
8187
# assume this is a number....
8188
return self.mav.messages['HEARTBEAT'].custom_mode == mode
8189
8190
def wait_mode(self, mode, timeout=60):
8191
"""Wait for mode to change."""
8192
self.progress("Waiting for mode %s" % mode)
8193
tstart = self.get_sim_time()
8194
while not self.mode_is(mode, drain_mav=False):
8195
custom_num = self.mav.messages['HEARTBEAT'].custom_mode
8196
self.progress("mav.flightmode=%s Want=%s custom=%u" % (
8197
self.mav.flightmode, mode, custom_num))
8198
if (timeout is not None and
8199
self.get_sim_time_cached() > tstart + timeout):
8200
raise WaitModeTimeout("Did not change mode")
8201
self.progress("Got mode %s" % mode)
8202
8203
def assert_mode_is(self, mode):
8204
if not self.mode_is(mode):
8205
raise NotAchievedException("Expected mode %s" % str(mode))
8206
8207
def get_mode(self, cached=False, drain_mav=True):
8208
'''return numeric custom mode'''
8209
if not cached:
8210
self.wait_heartbeat(drain_mav=drain_mav)
8211
return self.mav.messages['HEARTBEAT'].custom_mode
8212
8213
def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30):
8214
self.progress("Waiting for GPS health")
8215
tstart = self.get_sim_time()
8216
while True:
8217
now = self.get_sim_time_cached()
8218
if now - tstart > timeout:
8219
raise AutoTestTimeoutException("GPS status bits did not become good")
8220
m = self.mav.recv_match(type='SYS_STATUS', blocking=True, timeout=1)
8221
if m is None:
8222
continue
8223
if (not (m.onboard_control_sensors_present & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8224
self.progress("GPS not present")
8225
if now > 20:
8226
# it's had long enough to be detected....
8227
return
8228
continue
8229
if (not (m.onboard_control_sensors_enabled & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8230
self.progress("GPS not enabled")
8231
continue
8232
if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)):
8233
self.progress("GPS not healthy")
8234
continue
8235
self.progress("GPS healthy after %f/%f seconds" %
8236
((now - tstart), timeout))
8237
return
8238
8239
def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False):
8240
return self.sensor_has_state(sensor, present, enabled, healthy, do_assert=True, verbose=verbose)
8241
8242
def sensor_has_state(self, sensor, present=True, enabled=True, healthy=True, do_assert=False, verbose=False):
8243
m = self.assert_receive_message('SYS_STATUS', timeout=5, very_verbose=verbose)
8244
reported_present = m.onboard_control_sensors_present & sensor
8245
reported_enabled = m.onboard_control_sensors_enabled & sensor
8246
reported_healthy = m.onboard_control_sensors_health & sensor
8247
if present:
8248
if not reported_present:
8249
if do_assert:
8250
raise NotAchievedException("Sensor not present")
8251
return False
8252
else:
8253
if reported_present:
8254
if do_assert:
8255
raise NotAchievedException("Sensor present when it shouldn't be")
8256
return False
8257
8258
if enabled:
8259
if not reported_enabled:
8260
if do_assert:
8261
raise NotAchievedException("Sensor not enabled")
8262
return False
8263
else:
8264
if reported_enabled:
8265
if do_assert:
8266
raise NotAchievedException("Sensor enabled when it shouldn't be")
8267
return False
8268
8269
if healthy:
8270
if not reported_healthy:
8271
if do_assert:
8272
raise NotAchievedException("Sensor not healthy")
8273
return False
8274
else:
8275
if reported_healthy:
8276
if do_assert:
8277
raise NotAchievedException("Sensor healthy when it shouldn't be")
8278
return False
8279
return True
8280
8281
def wait_sensor_state(self, sensor, present=True, enabled=True, healthy=True, timeout=5, verbose=False):
8282
tstart = self.get_sim_time()
8283
while True:
8284
if self.get_sim_time_cached() - tstart > timeout:
8285
raise NotAchievedException("Sensor did not achieve state")
8286
if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose):
8287
break
8288
8289
def wait_not_ready_to_arm(self):
8290
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False)
8291
8292
def wait_prearm_sys_status_healthy(self, timeout=60):
8293
self.do_timesync_roundtrip()
8294
tstart = self.get_sim_time()
8295
while True:
8296
t2 = self.get_sim_time_cached()
8297
if t2 - tstart > timeout:
8298
self.progress("Prearm bit never went true. Attempting arm to elicit reason from autopilot")
8299
try:
8300
self.arm_vehicle()
8301
except Exception:
8302
pass
8303
raise AutoTestTimeoutException("Prearm bit never went true")
8304
if self.sensor_has_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, True):
8305
break
8306
8307
def assert_fence_enabled(self, timeout=2):
8308
# Check fence is enabled
8309
m = self.assert_receive_message('FENCE_STATUS', timeout=timeout)
8310
self.progress("Got (%s)" % str(m))
8311
8312
def assert_fence_disabled(self, timeout=2):
8313
# Check fence is not enabled
8314
self.assert_not_receiving_message('FENCE_STATUS', timeout=timeout)
8315
8316
def NoArmWithoutMissionItems(self):
8317
'''ensure we can't arm in auto mode without mission items present'''
8318
# load a trivial mission
8319
items = []
8320
items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 20000),)
8321
items.append((mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0))
8322
self.upload_simple_relhome_mission(items)
8323
8324
self.change_mode('AUTO')
8325
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
8326
self.assert_prearm_failure('Mode requires mission',
8327
other_prearm_failures_fatal=False)
8328
8329
def assert_prearm_failure(self,
8330
expected_statustext,
8331
timeout=5,
8332
ignore_prearm_failures=[],
8333
other_prearm_failures_fatal=True):
8334
seen_statustext = False
8335
seen_command_ack = False
8336
8337
self.drain_mav()
8338
tstart = self.get_sim_time_cached()
8339
arm_last_send = 0
8340
while True:
8341
if seen_command_ack and seen_statustext:
8342
break
8343
now = self.get_sim_time_cached()
8344
if now - tstart > timeout:
8345
raise NotAchievedException(
8346
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
8347
(seen_statustext, seen_command_ack))
8348
if now - arm_last_send > 1:
8349
arm_last_send = now
8350
self.send_mavlink_run_prearms_command()
8351
m = self.mav.recv_match(blocking=True, timeout=1)
8352
if m is None:
8353
continue
8354
if m.get_type() == "STATUSTEXT":
8355
if expected_statustext in m.text:
8356
self.progress("Got: %s" % str(m))
8357
seen_statustext = True
8358
elif other_prearm_failures_fatal and "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
8359
self.progress("Got: %s" % str(m))
8360
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
8361
8362
if m.get_type() == "COMMAND_ACK":
8363
print("Got: %s" % str(m))
8364
if m.command == mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS:
8365
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
8366
raise NotAchievedException("command-ack says we didn't run prearms")
8367
self.progress("Got: %s" % str(m))
8368
seen_command_ack = True
8369
if self.mav.motors_armed():
8370
raise NotAchievedException("Armed when we shouldn't have")
8371
8372
def assert_arm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]):
8373
seen_statustext = False
8374
seen_command_ack = False
8375
8376
self.drain_mav()
8377
tstart = self.get_sim_time_cached()
8378
arm_last_send = 0
8379
while True:
8380
if seen_command_ack and seen_statustext:
8381
break
8382
now = self.get_sim_time_cached()
8383
if now - tstart > timeout:
8384
raise NotAchievedException(
8385
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
8386
(seen_statustext, seen_command_ack))
8387
if now - arm_last_send > 1:
8388
arm_last_send = now
8389
self.send_mavlink_arm_command()
8390
m = self.mav.recv_match(blocking=True, timeout=1)
8391
if m is None:
8392
continue
8393
if m.get_type() == "STATUSTEXT":
8394
if expected_statustext in m.text:
8395
self.progress("Got: %s" % str(m))
8396
seen_statustext = True
8397
elif "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures:
8398
self.progress("Got: %s" % str(m))
8399
raise NotAchievedException("Unexpected prearm failure (%s)" % m.text)
8400
8401
if m.get_type() == "COMMAND_ACK":
8402
print("Got: %s" % str(m))
8403
if m.command == mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM:
8404
if m.result != 4:
8405
raise NotAchievedException("command-ack says we didn't fail to arm")
8406
self.progress("Got: %s" % str(m))
8407
seen_command_ack = True
8408
if self.mav.motors_armed():
8409
raise NotAchievedException("Armed when we shouldn't have")
8410
8411
def wait_ready_to_arm(self, timeout=120, require_absolute=True, check_prearm_bit=True):
8412
# wait for EKF checks to pass
8413
self.progress("Waiting for ready to arm")
8414
start = self.get_sim_time()
8415
self.wait_ekf_happy(timeout=timeout, require_absolute=require_absolute)
8416
if require_absolute:
8417
self.wait_gps_sys_status_not_present_or_enabled_and_healthy()
8418
if require_absolute:
8419
self.poll_home_position()
8420
if check_prearm_bit:
8421
self.wait_prearm_sys_status_healthy(timeout=timeout)
8422
armable_time = self.get_sim_time() - start
8423
self.progress("Took %u seconds to become armable" % armable_time)
8424
self.total_waiting_to_arm_time += armable_time
8425
self.waiting_to_arm_count += 1
8426
8427
def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x):
8428
'''as opposed to mav.wait_heartbeat, raises an exception on timeout.
8429
Also, ignores heartbeats not from our target system'''
8430
if drain_mav:
8431
self.drain_mav(quiet=quiet)
8432
orig_timeout = x.get("timeout", 20)
8433
x["timeout"] = 1
8434
tstart = time.time()
8435
while True:
8436
if time.time() - tstart > orig_timeout and not self.gdb:
8437
if not self.sitl_is_running():
8438
self.progress("SITL is not running")
8439
raise AutoTestTimeoutException("Did not receive heartbeat")
8440
m = self.mav.wait_heartbeat(*args, **x)
8441
if m is None:
8442
continue
8443
if m.get_srcSystem() == self.sysid_thismav():
8444
return m
8445
8446
def wait_ekf_happy(self, require_absolute=True, **kwargs):
8447
"""Wait for EKF to be happy"""
8448
if "timeout" not in kwargs:
8449
kwargs["timeout"] = 45
8450
8451
""" if using SITL estimates directly """
8452
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
8453
return True
8454
8455
# all of these must be set for arming to happen:
8456
required_value = (mavutil.mavlink.EKF_ATTITUDE |
8457
mavutil.mavlink.ESTIMATOR_VELOCITY_HORIZ |
8458
mavutil.mavlink.ESTIMATOR_VELOCITY_VERT |
8459
mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL |
8460
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_REL)
8461
# none of these bits must be set for arming to happen:
8462
error_bits = (mavutil.mavlink.ESTIMATOR_CONST_POS_MODE |
8463
mavutil.mavlink.ESTIMATOR_ACCEL_ERROR)
8464
if require_absolute:
8465
required_value |= (mavutil.mavlink.ESTIMATOR_POS_HORIZ_ABS |
8466
mavutil.mavlink.ESTIMATOR_POS_VERT_ABS |
8467
mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS)
8468
error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH
8469
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()
8470
8471
def wait_ekf_flags(self, required_value, error_bits, **kwargs):
8472
WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run()
8473
8474
def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30):
8475
"""Disable GPS and wait for EKF to report the end of assistance from GPS."""
8476
self.set_parameter("SIM_GPS1_ENABLE", 0)
8477
tstart = self.get_sim_time()
8478
8479
""" if using SITL estimates directly """
8480
if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10):
8481
self.progress("GPS disable skipped")
8482
return
8483
8484
# all of these must NOT be set for arming NOT to happen:
8485
not_required_value = 0
8486
if position_horizontal:
8487
not_required_value |= mavutil.mavlink.ESTIMATOR_POS_HORIZ_REL
8488
if position_vertical:
8489
not_required_value |= mavutil.mavlink.ESTIMATOR_POS_VERT_AGL
8490
self.progress("Waiting for EKF not having bits %u" % not_required_value)
8491
last_print_time = 0
8492
while timeout is None or self.get_sim_time_cached() < tstart + timeout:
8493
esr = self.assert_receive_message('EKF_STATUS_REPORT', timeout=timeout)
8494
current = esr.flags
8495
if self.get_sim_time_cached() - last_print_time > 1:
8496
self.progress("Wait EKF.flags: not required:%u current:%u" %
8497
(not_required_value, current))
8498
last_print_time = self.get_sim_time_cached()
8499
if current & not_required_value != not_required_value:
8500
self.progress("GPS disable OK")
8501
return
8502
self.progress(f"Last EKF_STATUS_REPORT: {esr}")
8503
raise AutoTestTimeoutException("Failed to get EKF.flags=%u disabled" % not_required_value)
8504
8505
def wait_text(self, *args, **kwargs):
8506
'''wait for text to appear from vehicle, return that text'''
8507
statustext = self.wait_statustext(*args, **kwargs)
8508
if statustext is None:
8509
return None
8510
return statustext.text
8511
8512
def statustext_in_collections(self, text, regex=False):
8513
'''searches for text in STATUSTEXT collection, returns message if found'''
8514
c = self.context_get()
8515
if "STATUSTEXT" not in c.collections:
8516
raise NotAchievedException("Asked to check context but it isn't collecting!")
8517
for x in c.collections["STATUSTEXT"]:
8518
self.progress(" statustext got=(%s) want=(%s)" % (x.text, text))
8519
if regex:
8520
if re.match(text, x.text):
8521
return x
8522
elif text.lower() in x.text.lower():
8523
return x
8524
return None
8525
8526
def wait_statustext(self, text, timeout=20, the_function=None, check_context=False, regex=False, wallclock_timeout=False):
8527
"""Wait for a specific STATUSTEXT, return that statustext message"""
8528
8529
# Statustexts are often triggered by something we've just
8530
# done, so we have to be careful not to read any traffic that
8531
# isn't checked for being our statustext. That doesn't work
8532
# well with getting the curent simulation time (which requires
8533
# a new SYSTEM_TIME message), so we install a message hook
8534
# which checks all incoming messages.
8535
self.progress("Waiting for text : %s" % text.lower())
8536
if check_context:
8537
statustext = self.statustext_in_collections(text, regex=regex)
8538
if statustext:
8539
self.progress("Found expected text in collection: %s" % text.lower())
8540
return statustext
8541
8542
global statustext_found
8543
global statustext_full
8544
statustext_full = None
8545
statustext_found = False
8546
8547
def mh(mav, m):
8548
global statustext_found
8549
global statustext_full
8550
if m.get_type() != "STATUSTEXT":
8551
return
8552
if regex:
8553
self.re_match = re.match(text, m.text)
8554
if self.re_match:
8555
statustext_found = True
8556
statustext_full = m
8557
if text.lower() in m.text.lower():
8558
self.progress("Received expected text: %s" % m.text.lower())
8559
statustext_found = True
8560
statustext_full = m
8561
8562
self.install_message_hook(mh)
8563
if wallclock_timeout:
8564
tstart = time.time()
8565
else:
8566
tstart = self.get_sim_time()
8567
try:
8568
while not statustext_found:
8569
if wallclock_timeout:
8570
now = time.time()
8571
else:
8572
now = self.get_sim_time_cached()
8573
if now - tstart > timeout:
8574
raise AutoTestTimeoutException("Failed to receive text: %s" %
8575
text.lower())
8576
if the_function is not None:
8577
the_function()
8578
self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)
8579
finally:
8580
self.remove_message_hook(mh)
8581
return statustext_full
8582
8583
# routines helpful for testing LUA scripting:
8584
def script_example_source_path(self, scriptname):
8585
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "examples", scriptname)
8586
8587
def script_test_source_path(self, scriptname):
8588
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", scriptname)
8589
8590
def script_applet_source_path(self, scriptname):
8591
return os.path.join(self.rootdir(), "libraries", "AP_Scripting", "applets", scriptname)
8592
8593
def installed_script_path(self, scriptname):
8594
return os.path.join("scripts", os.path.basename(scriptname))
8595
8596
def install_script(self, source, scriptname, install_name=None):
8597
if install_name is not None:
8598
dest = self.installed_script_path(install_name)
8599
else:
8600
dest = self.installed_script_path(scriptname)
8601
8602
destdir = os.path.dirname(dest)
8603
if not os.path.exists(destdir):
8604
os.mkdir(destdir)
8605
self.progress("Copying (%s) to (%s)" % (source, dest))
8606
shutil.copy(source, dest)
8607
8608
def installed_script_module_path(self, modulename):
8609
return os.path.join("scripts", "modules", os.path.basename(modulename))
8610
8611
def install_script_module(self, source, modulename, install_name=None):
8612
if install_name is not None:
8613
dest = self.installed_script_module_path(install_name)
8614
else:
8615
dest = self.installed_script_module_path(modulename)
8616
8617
destdir = os.path.dirname(dest)
8618
os.makedirs(destdir, exist_ok=True)
8619
self.progress("Copying (%s) to (%s)" % (source, dest))
8620
shutil.copy(source, dest)
8621
8622
def install_test_modules(self):
8623
source = os.path.join(self.rootdir(), "libraries", "AP_Scripting", "tests", "modules", "test")
8624
dest = os.path.join("scripts", "modules", "test")
8625
self.progress("Copying (%s) to (%s)" % (source, dest))
8626
shutil.copytree(source, dest)
8627
8628
def install_mavlink_module(self):
8629
dest = os.path.join("scripts", "modules", "mavlink")
8630
ardupilotmega_xml = os.path.join(self.rootdir(), "modules", "mavlink",
8631
"message_definitions", "v1.0", "ardupilotmega.xml")
8632
mavgen.mavgen(mavgen.Opts(output=dest, wire_protocol='2.0', language='Lua'), [ardupilotmega_xml])
8633
self.progress("Installed mavlink module")
8634
8635
def install_example_script(self, scriptname):
8636
source = self.script_example_source_path(scriptname)
8637
self.install_script(source, scriptname)
8638
8639
def install_test_script(self, scriptname):
8640
source = self.script_test_source_path(scriptname)
8641
self.install_script(source, scriptname)
8642
8643
def install_applet_script(self, scriptname, install_name=None):
8644
source = self.script_applet_source_path(scriptname)
8645
self.install_script(source, scriptname, install_name=install_name)
8646
8647
def remove_installed_script(self, scriptname):
8648
dest = self.installed_script_path(os.path.basename(scriptname))
8649
try:
8650
os.unlink(dest)
8651
except IOError:
8652
pass
8653
except OSError:
8654
pass
8655
8656
def remove_installed_script_module(self, modulename):
8657
path = self.installed_script_module_path(modulename)
8658
os.unlink(path)
8659
8660
def remove_installed_modules(self, modulename):
8661
dest = os.path.join("scripts", "modules", modulename)
8662
try:
8663
shutil.rmtree(dest)
8664
except IOError:
8665
pass
8666
except OSError:
8667
pass
8668
8669
def get_mavlink_connection_going(self):
8670
# get a mavlink connection going
8671
try:
8672
retries = 20
8673
if self.gdb:
8674
retries = 20000
8675
self.mav = mavutil.mavlink_connection(
8676
self.autotest_connection_string_to_ardupilot(),
8677
retries=retries,
8678
robust_parsing=True,
8679
source_system=250,
8680
source_component=250,
8681
autoreconnect=True,
8682
dialect="all", # if we don't pass this in we end up with the wrong mavlink version...
8683
)
8684
except Exception as msg:
8685
self.progress("Failed to start mavlink connection on %s: %s" %
8686
(self.autotest_connection_string_to_ardupilot(), msg,))
8687
raise
8688
self.mav.message_hooks.append(self.message_hook)
8689
self.mav.mav.set_send_callback(self.send_message_hook, self)
8690
self.mav.idle_hooks.append(self.idle_hook)
8691
8692
# we need to wait for a heartbeat here. If we don't then
8693
# self.mav.target_system will be zero because it hasn't
8694
# "locked on" to a target system yet.
8695
self.wait_heartbeat()
8696
self.set_streamrate(self.sitl_streamrate())
8697
8698
def show_test_timings_key_sorter(self, t):
8699
(k, v) = t
8700
return ((v, k))
8701
8702
def show_test_timings(self):
8703
if len(self.test_timings.keys()) == 0:
8704
return
8705
longest = 0
8706
for desc in self.test_timings.keys():
8707
if len(desc) > longest:
8708
longest = len(desc)
8709
tests_total_time = 0
8710
for desc, test_time in sorted(self.test_timings.items(),
8711
key=self.show_test_timings_key_sorter):
8712
fmt = "%" + str(longest) + "s: %.2fs"
8713
tests_total_time += test_time
8714
self.progress(fmt % (desc, test_time))
8715
self.progress(fmt % ("**--tests_total_time--**", tests_total_time))
8716
self.progress("mavproxy_start was called %u times" %
8717
(self.start_mavproxy_count,))
8718
self.progress("Supplied terrain data to autopilot in %u messages" %
8719
(self.terrain_data_messages_sent,))
8720
8721
def send_statustext(self, text):
8722
if sys.version_info.major >= 3 and not isinstance(text, bytes):
8723
text = bytes(text, "ascii")
8724
elif 'unicode' in str(type(text)):
8725
text = text.encode('ascii')
8726
seq = 0
8727
while len(text):
8728
self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text[:50], id=self.statustext_id, chunk_seq=seq)
8729
text = text[50:]
8730
seq += 1
8731
self.statustext_id += 1
8732
if self.statustext_id > 255:
8733
self.statustext_id = 1
8734
8735
def get_stacktrace(self):
8736
return ''.join(traceback.format_stack())
8737
8738
def get_exception_stacktrace(self, e):
8739
if sys.version_info[0] >= 3:
8740
ret = "%s\n" % e
8741
ret += ''.join(traceback.format_exception(type(e),
8742
e,
8743
tb=e.__traceback__))
8744
return ret
8745
8746
# Python2:
8747
return traceback.format_exc(e)
8748
8749
def bin_logs(self):
8750
return glob.glob("logs/*.BIN")
8751
8752
def remove_bin_logs(self):
8753
util.run_cmd('/bin/rm -f logs/*.BIN logs/LASTLOG.TXT')
8754
8755
def remove_ardupilot_terrain_cache(self):
8756
'''removes the terrain files ArduPilot keeps in its onboiard storage'''
8757
util.run_cmd('/bin/rm -f %s' % util.reltopdir("terrain/*.DAT"))
8758
8759
def check_logs(self, name):
8760
'''called to move relevant log files from our working directory to the
8761
buildlogs directory'''
8762
to_dir = self.logs_dir
8763
# move telemetry log files
8764
for log in glob.glob("autotest-*.tlog"):
8765
bname = os.path.basename(log)
8766
newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))
8767
print("Renaming %s to %s" % (log, newname))
8768
shutil.move(log, newname)
8769
# move binary log files
8770
for log in sorted(self.bin_logs()):
8771
bname = os.path.basename(log)
8772
newname = os.path.join(to_dir, "%s-%s-%s" % (self.log_name(), name, bname))
8773
print("Renaming %s to %s" % (log, newname))
8774
shutil.move(log, newname)
8775
# move core files
8776
save_binaries = False
8777
corefiles = []
8778
corefiles.extend(glob.glob("core*"))
8779
corefiles.extend(glob.glob("ap-*.core"))
8780
for log in sorted(corefiles):
8781
bname = os.path.basename(log)
8782
newname = os.path.join(to_dir, "%s-%s-%s" % (bname, self.log_name(), name))
8783
print("Renaming %s to %s" % (log, newname))
8784
shutil.move(log, newname)
8785
save_binaries = True
8786
if save_binaries:
8787
util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir,
8788
directory=util.reltopdir('.'))
8789
8790
def run_one_test(self, test, interact=False, suppress_stdout=False):
8791
'''new-style run-one-test used by run_tests'''
8792
for i in range(0, test.attempts-1):
8793
result = self.run_one_test_attempt(test, interact=interact, attempt=i+2, suppress_stdout=suppress_stdout)
8794
if result.passed:
8795
return result
8796
self.progress("Run attempt failed. Retrying")
8797
return self.run_one_test_attempt(test, interact=interact, attempt=1, suppress_stdout=suppress_stdout)
8798
8799
def print_exception_caught(self, e, send_statustext=True):
8800
self.progress("Exception caught: %s" %
8801
self.get_exception_stacktrace(e))
8802
path = None
8803
try:
8804
path = self.current_onboard_log_filepath()
8805
except IndexError:
8806
pass
8807
self.progress("Most recent logfile: %s" % (path, ), send_statustext=send_statustext)
8808
8809
def progress_file_content(self, filepath):
8810
with open(filepath) as f:
8811
for line in f:
8812
self.progress(line.rstrip())
8813
8814
def dump_process_status(self, result):
8815
'''used to show where the SITL process is upto. Often caused when
8816
we've lost contact'''
8817
8818
if self.sitl.isalive():
8819
self.progress("pexpect says it is alive")
8820
for tool in "dumpstack.sh", "dumpcore.sh":
8821
tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)
8822
if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:
8823
reason = "Failed %s" % (tool,)
8824
self.progress(reason)
8825
result.reason = reason
8826
result.passed = False
8827
else:
8828
self.progress("pexpect says it is dead")
8829
8830
# try dumping the process status file for more information:
8831
status_filepath = "/proc/%u/status" % self.sitl.pid
8832
self.progress("Checking for status filepath (%s)" % status_filepath)
8833
if os.path.exists(status_filepath):
8834
self.progress_file_content(status_filepath)
8835
else:
8836
self.progress("... does not exist")
8837
8838
def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=False):
8839
'''called by run_one_test to actually run the test in a retry loop'''
8840
name = test.name
8841
desc = test.description
8842
test_function = test.function
8843
test_kwargs = test.kwargs
8844
if attempt != 1:
8845
self.progress("RETRYING %s" % name)
8846
test_output_filename = self.buildlogs_path("%s-%s-retry-%u.txt" %
8847
(self.log_name(), name, attempt-1))
8848
else:
8849
test_output_filename = self.buildlogs_path("%s-%s.txt" %
8850
(self.log_name(), name))
8851
8852
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)
8853
8854
start_message_hooks = copy.copy(self.message_hooks)
8855
8856
prettyname = "%s (%s)" % (name, desc)
8857
self.start_test(prettyname)
8858
self.set_current_test_name(name)
8859
old_contexts_length = len(self.contexts)
8860
self.context_push()
8861
8862
start_time = time.time()
8863
8864
orig_speedup = None
8865
8866
hooks_removed = False
8867
8868
ex = None
8869
try:
8870
self.check_rc_defaults()
8871
self.change_mode(self.default_mode())
8872
# ArduPilot can still move the current waypoint from 0,
8873
# even if we are not in AUTO mode, so cehck_afterwards=False:
8874
self.set_current_waypoint(0, check_afterwards=False)
8875
self.drain_mav()
8876
self.drain_all_pexpects()
8877
if test.speedup is not None:
8878
self.progress("Overriding speedup to %u" % test.speedup)
8879
orig_speedup = self.get_parameter("SIM_SPEEDUP")
8880
self.set_parameter("SIM_SPEEDUP", test.speedup)
8881
8882
test_function(**test_kwargs)
8883
except Exception as e:
8884
self.print_exception_caught(e)
8885
ex = e
8886
# reset the message hooks; we've failed-via-exception and
8887
# can't expect the hooks to have been cleaned up
8888
for h in copy.copy(self.message_hooks):
8889
if h not in start_message_hooks:
8890
self.message_hooks.remove(h)
8891
hooks_removed = True
8892
self.test_timings[desc] = time.time() - start_time
8893
reset_needed = self.contexts[-1].sitl_commandline_customised
8894
8895
if orig_speedup is not None:
8896
self.set_parameter("SIM_SPEEDUP", orig_speedup)
8897
8898
passed = True
8899
if ex is not None:
8900
passed = False
8901
8902
result = Result(test)
8903
result.time_elapsed = self.test_timings[desc]
8904
8905
ardupilot_alive = False
8906
try:
8907
self.wait_heartbeat()
8908
ardupilot_alive = True
8909
except Exception:
8910
# process is dead
8911
self.progress("No heartbeat after test", send_statustext=False)
8912
self.dump_process_status(result)
8913
8914
passed = False
8915
reset_needed = True
8916
8917
try:
8918
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
8919
except Exception as e:
8920
self.print_exception_caught(e, send_statustext=False)
8921
passed = False
8922
8923
# if we haven't already reset ArduPilot because it's dead,
8924
# then ensure the vehicle was disarmed at the end of the test.
8925
# If it wasn't then the test is considered failed:
8926
if ardupilot_alive and self.armed() and not self.is_tracker():
8927
if ex is None:
8928
ex = ArmedAtEndOfTestException("Still armed at end of test")
8929
self.progress("Armed at end of test; force-rebooting SITL")
8930
self.set_rc_default() # otherwise we might start calibrating ESCs...
8931
try:
8932
self.disarm_vehicle(force=True)
8933
except AutoTestTimeoutException:
8934
reset_needed = True
8935
self.forced_post_test_sitl_reboots += 1
8936
if reset_needed:
8937
self.progress("Force-resetting SITL")
8938
self.reset_SITL_commandline()
8939
else:
8940
self.progress("Force-rebooting SITL")
8941
self.zero_throttle()
8942
self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it
8943
passed = False
8944
elif ardupilot_alive and not passed: # implicit reboot after a failed test:
8945
self.progress("Test failed but ArduPilot process alive; rebooting")
8946
self.reboot_sitl() # that'll learn it
8947
8948
if self._mavproxy is not None:
8949
self.progress("Stopping auto-started mavproxy")
8950
if self.use_map:
8951
self.mavproxy.send("module unload map\n")
8952
self.mavproxy.expect("Unloaded module map")
8953
8954
self.expect_list_remove(self._mavproxy)
8955
util.pexpect_close(self._mavproxy)
8956
self._mavproxy = None
8957
8958
corefiles = []
8959
corefiles.extend(glob.glob("core*"))
8960
corefiles.extend(glob.glob("ap-*.core"))
8961
if corefiles:
8962
self.progress('Corefiles detected: %s' % str(corefiles))
8963
passed = False
8964
8965
if len(self.contexts) != old_contexts_length:
8966
self.progress("context count mismatch (want=%u got=%u); popping extras" %
8967
(old_contexts_length, len(self.contexts)))
8968
passed = False
8969
# pop off old contexts to clean up message hooks etc
8970
while len(self.contexts) > old_contexts_length:
8971
try:
8972
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
8973
except Exception as e:
8974
self.print_exception_caught(e, send_statustext=False)
8975
self.progress("Done popping extra contexts")
8976
8977
# make sure we don't leave around stray listeners:
8978
if len(self.message_hooks) != len(start_message_hooks):
8979
self.progress("Stray message listeners: %s vs start %s" %
8980
(str(self.message_hooks), str(start_message_hooks)))
8981
passed = False
8982
8983
if passed:
8984
# 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
8985
pass
8986
else:
8987
if self.logs_dir is not None:
8988
# stash the binary logs and corefiles away for later analysis
8989
self.check_logs(name)
8990
8991
if passed:
8992
self.progress('PASSED: "%s"' % prettyname)
8993
else:
8994
self.progress('FAILED: "%s": %s (see %s)' %
8995
(prettyname, repr(ex), test_output_filename))
8996
result.exception = ex
8997
result.debug_filename = test_output_filename
8998
if interact:
8999
self.progress("Starting MAVProxy interaction as directed")
9000
self.mavproxy.interact()
9001
9002
if self.reset_after_every_test:
9003
reset_needed = True
9004
9005
if reset_needed:
9006
self.reset_SITL_commandline()
9007
9008
if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling
9009
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
9010
self.set_current_waypoint(0, check_afterwards=False)
9011
9012
tee.close()
9013
9014
result.passed = passed
9015
return result
9016
9017
def defaults_filepath(self):
9018
return None
9019
9020
def start_mavproxy(self, sitl_rcin_port=None, master=None, options=None):
9021
self.start_mavproxy_count += 1
9022
if self.mavproxy is not None:
9023
return self.mavproxy
9024
self.progress("Starting MAVProxy")
9025
9026
# determine a good pexpect timeout for reading MAVProxy's
9027
# output; some regmes may require longer timeouts.
9028
pexpect_timeout = 60
9029
if self.valgrind or self.callgrind:
9030
pexpect_timeout *= 10
9031
9032
if sitl_rcin_port is None:
9033
sitl_rcin_port = self.sitl_rcin_port()
9034
9035
if master is None:
9036
master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762)
9037
9038
if options is None:
9039
options = self.mavproxy_options()
9040
else:
9041
op = self.mavproxy_options().copy()
9042
op.extend(options)
9043
options = op
9044
9045
mavproxy = util.start_MAVProxy_SITL(
9046
self.vehicleinfo_key(),
9047
master=master,
9048
logfile=self.mavproxy_logfile,
9049
options=options,
9050
pexpect_timeout=pexpect_timeout,
9051
sitl_rcin_port=sitl_rcin_port,
9052
)
9053
mavproxy.expect(r'Telemetry log: (\S+)\r\n')
9054
self.logfile = mavproxy.match.group(1)
9055
self.progress("LOGFILE %s" % self.logfile)
9056
self.try_symlink_tlog()
9057
9058
self.expect_list_add(mavproxy)
9059
util.expect_setup_callback(mavproxy, self.expect_callback)
9060
self._mavproxy = mavproxy # so we can clean up after tests....
9061
return mavproxy
9062
9063
def stop_mavproxy(self, mavproxy):
9064
if self.mavproxy is not None:
9065
return
9066
self.progress("Stopping MAVProxy")
9067
self.expect_list_remove(mavproxy)
9068
util.pexpect_close(mavproxy)
9069
self._mavproxy = None
9070
9071
def start_SITL(self, binary=None, sitl_home=None, **sitl_args):
9072
if sitl_home is None:
9073
sitl_home = self.sitl_home()
9074
start_sitl_args = {
9075
"breakpoints": self.breakpoints,
9076
"disable_breakpoints": self.disable_breakpoints,
9077
"gdb": self.gdb,
9078
"gdb_no_tui": self.gdb_no_tui,
9079
"gdbserver": self.gdbserver,
9080
"lldb": self.lldb,
9081
"home": sitl_home,
9082
"speedup": self.speedup,
9083
"valgrind": self.valgrind,
9084
"callgrind": self.callgrind,
9085
"wipe": True,
9086
"enable_fgview": self.enable_fgview,
9087
}
9088
start_sitl_args.update(**sitl_args)
9089
if ("defaults_filepath" not in start_sitl_args or
9090
start_sitl_args["defaults_filepath"] is None):
9091
start_sitl_args["defaults_filepath"] = self.defaults_filepath()
9092
9093
if "model" not in start_sitl_args or start_sitl_args["model"] is None:
9094
start_sitl_args["model"] = self.frame
9095
self.progress("Starting SITL", send_statustext=False)
9096
if binary is None:
9097
binary = self.binary
9098
self.sitl = util.start_SITL(binary, **start_sitl_args)
9099
self.expect_list_add(self.sitl)
9100
self.sup_prog = []
9101
count = 0
9102
for sup_binary in self.sup_binaries:
9103
self.progress("Starting Supplementary Program ", sup_binary)
9104
start_sitl_args["customisations"] = [sup_binary['customisation']]
9105
start_sitl_args["supplementary"] = True
9106
start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count)
9107
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
9108
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
9109
self.sup_prog.append(sup_prog_link)
9110
self.expect_list_add(sup_prog_link)
9111
count += 1
9112
9113
# mavlink will have disconnected here. Explicitly reconnect,
9114
# or the first packet we send will be lost:
9115
if self.mav is not None:
9116
self.mav.reconnect()
9117
9118
def get_supplementary_programs(self):
9119
return self.sup_prog
9120
9121
def stop_sup_program(self, instance=None):
9122
self.progress("Stopping supplementary program")
9123
if instance is None:
9124
# close all sup programs
9125
for prog in self.sup_prog:
9126
self.expect_list_remove(prog)
9127
self.sup_prog.remove(prog)
9128
util.pexpect_close(prog)
9129
else:
9130
# close only the instance passed
9131
prog = self.sup_prog[instance]
9132
self.expect_list_remove(prog)
9133
self.sup_prog[instance] = None
9134
util.pexpect_close(prog)
9135
9136
def start_sup_program(self, instance=None, args=None):
9137
self.progress("Starting supplementary program")
9138
start_sitl_args = {
9139
"breakpoints": self.breakpoints,
9140
"disable_breakpoints": self.disable_breakpoints,
9141
"gdb": self.gdb,
9142
"gdb_no_tui": self.gdb_no_tui,
9143
"gdbserver": self.gdbserver,
9144
"lldb": self.lldb,
9145
"home": self.sitl_home(),
9146
"speedup": self.speedup,
9147
"valgrind": self.valgrind,
9148
"callgrind": self.callgrind,
9149
"wipe": True,
9150
}
9151
for i in range(len(self.sup_binaries)):
9152
if instance is not None and instance != i:
9153
continue
9154
sup_binary = self.sup_binaries[i]
9155
start_sitl_args["customisations"] = [sup_binary['customisation']]
9156
if args is not None:
9157
start_sitl_args["customisations"] = [sup_binary['customisation'], args]
9158
start_sitl_args["supplementary"] = True
9159
start_sitl_args["defaults_filepath"] = sup_binary['param_file']
9160
sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args)
9161
time.sleep(1)
9162
self.sup_prog[i] = sup_prog_link # add to list
9163
self.expect_list_add(sup_prog_link) # add to expect list
9164
9165
def sitl_is_running(self):
9166
if self.sitl is None:
9167
return False
9168
return self.sitl.isalive()
9169
9170
def autostart_mavproxy(self):
9171
return self.use_map
9172
9173
def init(self):
9174
"""Initilialize autotest feature."""
9175
self.mavproxy_logfile = self.open_mavproxy_logfile()
9176
9177
if self.frame is None:
9178
self.frame = self.default_frame()
9179
9180
if self.frame is None:
9181
raise ValueError("frame must not be None")
9182
9183
self.progress("Starting simulator")
9184
self.start_SITL()
9185
9186
os.environ['MAVLINK20'] = '1'
9187
9188
self.progress("Starting MAVLink connection")
9189
self.get_mavlink_connection_going()
9190
9191
if self.autostart_mavproxy():
9192
self.mavproxy = self.start_mavproxy()
9193
9194
self.expect_list_clear()
9195
self.expect_list_extend([self.sitl, self.mavproxy])
9196
self.expect_list_extend(self.sup_prog)
9197
9198
# need to wait for a heartbeat to arrive as then mavutil will
9199
# select the correct set of messages for us to receive in
9200
# self.mav.messages. You can actually receive messages with
9201
# recv_match and those will not be in self.mav.messages until
9202
# you do this!
9203
self.wait_heartbeat()
9204
self.get_autopilot_firmware_version()
9205
self.progress("Sim time: %f" % (self.get_sim_time(),))
9206
self.apply_default_parameters()
9207
9208
if not self.sitl_is_running():
9209
# we run this just to make sure exceptions are likely to
9210
# work OK.
9211
raise NotAchievedException("SITL is not running")
9212
self.progress("SITL is running")
9213
9214
self.progress("Ready to start testing!")
9215
9216
def upload_using_mission_protocol(self, mission_type, items):
9217
'''mavlink2 required'''
9218
target_system = 1
9219
target_component = 1
9220
self.do_timesync_roundtrip()
9221
tstart = self.get_sim_time()
9222
self.mav.mav.mission_count_send(target_system,
9223
target_component,
9224
len(items),
9225
mission_type)
9226
remaining_to_send = set(range(0, len(items)))
9227
sent = set()
9228
timeout = (10 + len(items)/10.0)
9229
while True:
9230
if self.get_sim_time_cached() - tstart > timeout:
9231
raise NotAchievedException("timeout uploading %s" % str(mission_type))
9232
if len(remaining_to_send) == 0:
9233
self.progress("All sent")
9234
break
9235
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],
9236
blocking=True,
9237
timeout=1)
9238
if m is None:
9239
continue
9240
9241
if m.get_type() == 'MISSION_ACK':
9242
if (m.target_system == 255 and
9243
m.target_component == 0 and
9244
m.type == 1 and
9245
m.mission_type == 0):
9246
# this is just MAVProxy trying to screw us up
9247
continue
9248
raise NotAchievedException(f"Received unexpected mission ack {self.dump_message_verbose(m)}")
9249
9250
self.progress("Handling request for item %u/%u" % (m.seq, len(items)-1))
9251
self.progress("Item (%s)" % str(items[m.seq]))
9252
if m.seq in sent:
9253
self.progress("received duplicate request for item %u" % m.seq)
9254
continue
9255
9256
if m.seq not in remaining_to_send:
9257
raise NotAchievedException("received request for unknown item %u" % m.seq)
9258
9259
if m.mission_type != mission_type:
9260
raise NotAchievedException("received request for item from wrong mission type")
9261
9262
if items[m.seq].mission_type != mission_type:
9263
raise NotAchievedException(f"supplied item not of correct mission type (want={mission_type} got={items[m.seq].mission_type}") # noqa:501
9264
if items[m.seq].target_system != target_system:
9265
raise NotAchievedException("supplied item not of correct target system")
9266
if items[m.seq].target_component != target_component:
9267
raise NotAchievedException("supplied item not of correct target component")
9268
if items[m.seq].seq != m.seq:
9269
raise NotAchievedException("supplied item has incorrect sequence number (%u vs %u)" %
9270
(items[m.seq].seq, m.seq))
9271
9272
items[m.seq].pack(self.mav.mav)
9273
self.mav.mav.send(items[m.seq])
9274
remaining_to_send.discard(m.seq)
9275
sent.add(m.seq)
9276
9277
timeout += 10 # we received a good request for item; be generous with our timeouts
9278
9279
m = self.assert_receive_message('MISSION_ACK', timeout=1)
9280
if m.mission_type != mission_type:
9281
raise NotAchievedException("Mission ack not of expected mission type")
9282
if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:
9283
raise NotAchievedException("Mission upload failed (%s)" %
9284
(mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),)
9285
self.progress("Upload of all %u items succeeded" % len(items))
9286
9287
def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10):
9288
'''mavlink2 required'''
9289
target_system = 1
9290
target_component = 1
9291
self.progress("Sending mission_request_list")
9292
tstart = self.get_sim_time()
9293
self.mav.mav.mission_request_list_send(target_system,
9294
target_component,
9295
mission_type)
9296
9297
while True:
9298
if self.get_sim_time_cached() - tstart > timeout:
9299
raise NotAchievedException("Did not get MISSION_COUNT packet")
9300
m = self.mav.recv_match(blocking=True, timeout=0.1)
9301
if m is None:
9302
raise NotAchievedException("Did not get MISSION_COUNT response")
9303
if verbose:
9304
self.progress(str(m))
9305
if m.get_type() == 'MISSION_ACK':
9306
if m.target_system == 255 and m.target_component == 0:
9307
# this was for MAVProxy
9308
continue
9309
self.progress("Mission ACK: %s" % str(m))
9310
raise NotAchievedException("Received MISSION_ACK while waiting for MISSION_COUNT")
9311
if m.get_type() != 'MISSION_COUNT':
9312
continue
9313
if m.target_component != self.mav.source_system:
9314
continue
9315
if m.mission_type != mission_type:
9316
raise NotAchievedException("Mission count response of incorrect type")
9317
break
9318
9319
items = []
9320
tstart = self.get_sim_time_cached()
9321
remaining_to_receive = set(range(0, m.count))
9322
next_to_request = 0
9323
timeout = m.count
9324
timeout *= self.speedup / 10.0
9325
timeout += 10
9326
while True:
9327
delta_t = self.get_sim_time_cached() - tstart
9328
if delta_t > timeout:
9329
raise NotAchievedException(
9330
"timeout downloading type=%s after %s seconds of %s allowed" %
9331
(mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name,
9332
delta_t, timeout))
9333
if len(remaining_to_receive) == 0:
9334
self.progress("All received")
9335
return items
9336
self.progress("Requesting item %u (remaining=%u)" %
9337
(next_to_request, len(remaining_to_receive)))
9338
self.mav.mav.mission_request_int_send(target_system,
9339
target_component,
9340
next_to_request,
9341
mission_type)
9342
m = self.mav.recv_match(type='MISSION_ITEM_INT',
9343
blocking=True,
9344
timeout=5,
9345
condition='MISSION_ITEM_INT.mission_type==%u' % mission_type)
9346
if m is None:
9347
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
9348
if m.target_system != self.mav.source_system:
9349
raise NotAchievedException("Wrong target system (want=%u got=%u)" %
9350
(self.mav.source_system, m.target_system))
9351
if m.target_component != self.mav.source_component:
9352
raise NotAchievedException("Wrong target component")
9353
self.progress("Got (%s)" % str(m))
9354
if m.mission_type != mission_type:
9355
raise NotAchievedException("Received waypoint of wrong type")
9356
if m.seq != next_to_request:
9357
raise NotAchievedException("Received waypoint is out of sequence")
9358
self.progress("Item %u OK" % m.seq)
9359
timeout += 10 # we received an item; be generous with our timeouts
9360
items.append(m)
9361
next_to_request += 1
9362
remaining_to_receive.discard(m.seq)
9363
9364
def dump_message_verbose(self, m):
9365
'''return verbose dump of m. Wraps the pymavlink routine which
9366
inconveniently takes a filehandle'''
9367
f = StringIO.StringIO()
9368
mavutil.dump_message_verbose(f, m)
9369
return f.getvalue()
9370
9371
def poll_home_position(self, quiet=True, timeout=30):
9372
old = self.mav.messages.get("HOME_POSITION", None)
9373
tstart = self.get_sim_time()
9374
while True:
9375
if self.get_sim_time_cached() - tstart > timeout:
9376
raise NotAchievedException("Failed to poll home position")
9377
if not quiet:
9378
self.progress("Sending MAV_CMD_GET_HOME_POSITION")
9379
try:
9380
self.run_cmd(
9381
mavutil.mavlink.MAV_CMD_GET_HOME_POSITION,
9382
quiet=quiet,
9383
)
9384
except ValueError:
9385
continue
9386
m = self.mav.messages.get("HOME_POSITION", None)
9387
if m is None:
9388
continue
9389
if old is None:
9390
break
9391
if m._timestamp != old._timestamp:
9392
break
9393
self.progress("Polled home position (%s)" % str(m))
9394
return m
9395
9396
def position_target_loc(self):
9397
'''returns target location based on POSITION_TARGET_GLOBAL_INT'''
9398
m = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)
9399
return mavutil.location(m.lat_int*1e-7, m.lon_int*1e-7, m.alt)
9400
9401
def current_waypoint(self):
9402
m = self.assert_receive_message('MISSION_CURRENT')
9403
return m.seq
9404
9405
def distance_to_nav_target(self, use_cached_nav_controller_output=False):
9406
'''returns distance to waypoint navigation target in metres'''
9407
m = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None)
9408
if m is None or not use_cached_nav_controller_output:
9409
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=10)
9410
return m.wp_dist
9411
9412
def distance_to_home(self, use_cached_home=False):
9413
m = self.mav.messages.get("HOME_POSITION", None)
9414
if use_cached_home is False or m is None:
9415
m = self.poll_home_position(quiet=True)
9416
here = self.assert_receive_message('GLOBAL_POSITION_INT')
9417
return self.get_distance_int(m, here)
9418
9419
def home_position_as_mav_location(self):
9420
m = self.poll_home_position()
9421
return mavutil.location(m.latitude*1.0e-7, m.longitude*1.0e-7, m.altitude*1.0e-3, 0)
9422
9423
def offset_location_ne(self, location, metres_north, metres_east):
9424
'''return a new location offset from passed-in location'''
9425
(target_lat, target_lng) = mavextra.gps_offset(location.lat,
9426
location.lng,
9427
metres_east,
9428
metres_north)
9429
return mavutil.location(target_lat,
9430
target_lng,
9431
location.alt,
9432
location.heading)
9433
9434
def offset_location_heading_distance(self, location, bearing, distance):
9435
(target_lat, target_lng) = mavextra.gps_newpos(
9436
location.lat,
9437
location.lng,
9438
bearing,
9439
distance
9440
)
9441
return mavutil.location(
9442
target_lat,
9443
target_lng,
9444
location.alt,
9445
location.heading
9446
)
9447
9448
def monitor_groundspeed(self, want, tolerance=0.5, timeout=5):
9449
tstart = self.get_sim_time()
9450
while True:
9451
if self.get_sim_time_cached() - tstart > timeout:
9452
break
9453
m = self.assert_receive_message('VFR_HUD', timeout=timeout)
9454
if m.groundspeed > want+tolerance:
9455
raise NotAchievedException("Too fast (%f > %f)" %
9456
(m.groundspeed, want))
9457
if m.groundspeed < want-tolerance:
9458
raise NotAchievedException("Too slow (%f < %f)" %
9459
(m.groundspeed, want))
9460
self.progress("GroundSpeed OK (got=%f) (want=%f)" %
9461
(m.groundspeed, want))
9462
9463
def set_home(self, loc):
9464
'''set home to supplied loc'''
9465
self.run_cmd_int(
9466
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9467
p5=int(loc.lat*1e7),
9468
p6=int(loc.lng*1e7),
9469
p7=loc.alt,
9470
)
9471
9472
def SetHome(self):
9473
'''Setting and fetching of home'''
9474
if self.is_tracker():
9475
# tracker starts armed...
9476
self.disarm_vehicle(force=True)
9477
self.reboot_sitl()
9478
9479
# HOME_POSITION is used as a surrogate for origin until we
9480
# start emitting GPS_GLOBAL_ORIGIN
9481
self.wait_ekf_happy()
9482
orig_home = self.poll_home_position()
9483
if orig_home is None:
9484
raise AutoTestTimeoutException()
9485
self.progress("Original home: %s" % str(orig_home))
9486
# original home should be close to SITL home...
9487
start_loc = self.sitl_start_location()
9488
self.progress("SITL start loc: %s" % str(start_loc))
9489
delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)
9490
if delta > 0.000006:
9491
raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %
9492
(orig_home.latitude * 1.0e-7, start_loc.lat, delta))
9493
delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)
9494
if delta > 0.000006:
9495
raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %
9496
(orig_home.longitude * 1.0e-7, start_loc.lng, delta))
9497
if self.is_rover():
9498
self.progress("### Rover skipping altitude check unti position fixes in")
9499
else:
9500
home_alt_m = orig_home.altitude * 1.0e-3
9501
if abs(home_alt_m - start_loc.alt) > 2: # metres
9502
raise ValueError("homes differ in alt got=%fm want=%fm" %
9503
(home_alt_m, start_loc.alt))
9504
new_x = orig_home.latitude + 1000
9505
new_y = orig_home.longitude + 2000
9506
new_z = orig_home.altitude + 300000 # 300 metres
9507
print("new home: %s %s %s" % (str(new_x), str(new_y), str(new_z)))
9508
self.run_cmd_int(
9509
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9510
p5=new_x,
9511
p6=new_y,
9512
p7=new_z/1000.0, # mm => m
9513
)
9514
9515
home = self.poll_home_position()
9516
self.progress("home: %s" % str(home))
9517
got_home_latitude = home.latitude
9518
got_home_longitude = home.longitude
9519
got_home_altitude = home.altitude
9520
if (got_home_latitude != new_x or
9521
got_home_longitude != new_y or
9522
abs(got_home_altitude - new_z) > 100): # float-conversion issues
9523
self.reboot_sitl()
9524
raise NotAchievedException(
9525
"Home mismatch got=(%f, %f, %f) set=(%f, %f, %f)" %
9526
(got_home_latitude, got_home_longitude, got_home_altitude,
9527
new_x, new_y, new_z))
9528
9529
self.progress("monitoring home to ensure it doesn't drift at all")
9530
tstart = self.get_sim_time()
9531
while self.get_sim_time_cached() - tstart < 10:
9532
home = self.poll_home_position(quiet=True)
9533
self.progress("home: %s" % str(home))
9534
if (home.latitude != got_home_latitude or
9535
home.longitude != got_home_longitude or
9536
home.altitude != got_home_altitude): # float-conversion issues
9537
self.reboot_sitl()
9538
raise NotAchievedException("home is drifting")
9539
9540
self.progress("Waiting for EKF to start")
9541
self.wait_ready_to_arm()
9542
self.progress("now use lat=0, lon=0 to reset home to current location")
9543
self.run_cmd_int(
9544
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9545
p5=0, # lat
9546
p6=0, # lon
9547
p7=new_z/1000.0, # mm => m
9548
)
9549
home = self.poll_home_position()
9550
self.progress("home: %s" % str(home))
9551
if self.distance_to_home(use_cached_home=True) > 1:
9552
raise NotAchievedException("Setting home to current location did not work")
9553
9554
self.progress("Setting home elsewhere again")
9555
self.run_cmd_int(
9556
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9557
p5=new_x,
9558
p6=new_y,
9559
p7=new_z/1000.0, # mm => m
9560
)
9561
if self.distance_to_home() < 10:
9562
raise NotAchievedException("Setting home to location did not work")
9563
9564
self.progress("use param1=1 to reset home to current location")
9565
self.run_cmd_int(
9566
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
9567
p1=1, # use current location
9568
p5=37, # lat
9569
p6=21, # lon
9570
p7=new_z/1000.0, # mm => m
9571
)
9572
home = self.poll_home_position()
9573
self.progress("home: %s" % str(home))
9574
if self.distance_to_home() > 1:
9575
raise NotAchievedException("Setting home to current location did not work")
9576
9577
if self.is_tracker():
9578
# tracker starts armed...
9579
self.disarm_vehicle(force=True)
9580
self.reboot_sitl()
9581
9582
def zero_mag_offset_parameters(self, compass_count=3):
9583
self.progress("Zeroing Mag OFS parameters")
9584
self.get_sim_time()
9585
zero_offset_parameters_hash = {}
9586
for num in "", "2", "3":
9587
for axis in "X", "Y", "Z":
9588
name = "COMPASS_OFS%s_%s" % (num, axis)
9589
zero_offset_parameters_hash[name] = 0
9590
self.set_parameters(zero_offset_parameters_hash)
9591
# force-save the calibration values:
9592
self.run_cmd_int(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, p2=76)
9593
self.progress("zeroed mag parameters")
9594
9595
params = [
9596
[("SIM_MAG1_OFS1_X", "COMPASS_OFS_X", 0),
9597
("SIM_MAG1_OFS1_Y", "COMPASS_OFS_Y", 0),
9598
("SIM_MAG1_OFS1_Z", "COMPASS_OFS_Z", 0), ],
9599
]
9600
for count in range(2, compass_count + 1):
9601
params += [
9602
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, 0),
9603
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, 0),
9604
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, 0), ],
9605
]
9606
self.check_zero_mag_parameters(params)
9607
9608
def forty_two_mag_dia_odi_parameters(self, compass_count=3):
9609
self.progress("Forty twoing Mag DIA and ODI parameters")
9610
self.get_sim_time()
9611
params = [
9612
[("SIM_MAG1_DIA_X", "COMPASS_DIA_X", 42.0),
9613
("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", 42.0),
9614
("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", 42.0),
9615
("SIM_MAG1_ODI_X", "COMPASS_ODI_X", 42.0),
9616
("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", 42.0),
9617
("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", 42.0), ],
9618
]
9619
for count in range(2, compass_count + 1):
9620
params += [
9621
[("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, 42.0),
9622
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, 42.0),
9623
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, 42.0),
9624
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, 42.0),
9625
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, 42.0),
9626
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, 42.0), ],
9627
]
9628
self.wait_heartbeat()
9629
to_set = {}
9630
for param_set in params:
9631
for param in param_set:
9632
(_, _out, value) = param
9633
to_set[_out] = value
9634
self.set_parameters(to_set)
9635
self.check_zero_mag_parameters(params)
9636
9637
def check_mag_parameters(self, parameter_stuff, compass_number):
9638
self.progress("Checking that Mag parameter")
9639
for idx in range(0, compass_number, 1):
9640
for param in parameter_stuff[idx]:
9641
(_in, _out, value) = param
9642
got_value = self.get_parameter(_out)
9643
if abs(got_value - value) > abs(value) * 0.15:
9644
raise NotAchievedException("%s/%s not within 15%%; got %f want=%f" % (_in, _out, got_value, value))
9645
9646
def check_zero_mag_parameters(self, parameter_stuff):
9647
self.progress("Checking that Mag OFS are zero")
9648
for param_set in parameter_stuff:
9649
for param in param_set:
9650
(_in, _out, _) = param
9651
got_value = self.get_parameter(_out)
9652
max = 0.15
9653
if "DIA" in _out or "ODI" in _out:
9654
max += 42.0
9655
if abs(got_value) > max:
9656
raise NotAchievedException(
9657
"%s/%s not within 15%%; got %f want=%f" %
9658
(_in, _out, got_value, 0.0 if max > 1 else 42.0))
9659
9660
def check_zeros_mag_orient(self, compass_count=3):
9661
self.progress("zeroed mag parameters")
9662
self.verify_parameter_values({"COMPASS_ORIENT": 0})
9663
for count in range(2, compass_count + 1):
9664
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0})
9665
9666
# this autotest appears to interfere with FixedYawCalibration, no idea why.
9667
def SITLCompassCalibration(self, compass_count=3, timeout=1000):
9668
'''Test Fixed Yaw Calibration"'''
9669
9670
timeout /= 8
9671
timeout *= self.speedup
9672
9673
def reset_pos_and_start_magcal(mavproxy, tmask):
9674
mavproxy.send("sitl_stop\n")
9675
mavproxy.send("sitl_attitude 0 0 0\n")
9676
self.get_sim_time()
9677
self.run_cmd(
9678
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
9679
p1=tmask, # p1: mag_mask
9680
p2=0, # retry
9681
p3=0, # autosave
9682
p4=0, # delay
9683
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
9684
timeout=20,
9685
)
9686
mavproxy.send("sitl_magcal\n")
9687
9688
def do_prep_mag_cal_test(mavproxy, params):
9689
self.progress("Preparing the vehicle for magcal")
9690
MAG_OFS = 100
9691
MAG_DIA = 1.0
9692
MAG_ODI = 0.004
9693
params += [
9694
[("SIM_MAG1_OFS_X", "COMPASS_OFS_X", MAG_OFS),
9695
("SIM_MAG1_OFS_Y", "COMPASS_OFS_Y", MAG_OFS + 100),
9696
("SIM_MAG1_OFS_Z", "COMPASS_OFS_Z", MAG_OFS + 200),
9697
("SIM_MAG1_DIA_X", "COMPASS_DIA_X", MAG_DIA),
9698
("SIM_MAG1_DIA_Y", "COMPASS_DIA_Y", MAG_DIA + 0.1),
9699
("SIM_MAG1_DIA_Z", "COMPASS_DIA_Z", MAG_DIA + 0.2),
9700
("SIM_MAG1_ODI_X", "COMPASS_ODI_X", MAG_ODI),
9701
("SIM_MAG1_ODI_Y", "COMPASS_ODI_Y", MAG_ODI + 0.001),
9702
("SIM_MAG1_ODI_Z", "COMPASS_ODI_Z", MAG_ODI + 0.001), ],
9703
]
9704
for count in range(2, compass_count + 1):
9705
params += [
9706
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),
9707
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),
9708
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),
9709
("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),
9710
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),
9711
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),
9712
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),
9713
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),
9714
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],
9715
]
9716
self.progress("Setting calibration mode")
9717
self.wait_heartbeat()
9718
self.customise_SITL_commandline(["-M", "calibration"])
9719
self.mavproxy_load_module(mavproxy, "sitl_calibration")
9720
self.mavproxy_load_module(mavproxy, "calibration")
9721
self.mavproxy_load_module(mavproxy, "relay")
9722
self.wait_statustext("is using GPS", timeout=60)
9723
mavproxy.send("accelcalsimple\n")
9724
mavproxy.expect("Calibrated")
9725
# disable it to not interfert with calibration acceptation
9726
self.mavproxy_unload_module(mavproxy, "calibration")
9727
if self.is_copter():
9728
# set frame class to pass arming check on copter
9729
self.set_parameter("FRAME_CLASS", 1)
9730
self.progress("Setting SITL Magnetometer model value")
9731
self.set_parameter("COMPASS_AUTO_ROT", 0)
9732
# MAG_ORIENT = 4
9733
# self.set_parameter("SIM_MAG1_ORIENT", MAG_ORIENT)
9734
# for count in range(2, compass_count + 1):
9735
# self.set_parameter("SIM_MAG%d_ORIENT" % count, MAG_ORIENT * (count % 41))
9736
# # set compass external to check that orientation is found and auto set
9737
# self.set_parameter("COMPASS_EXTERN%d" % count, 1)
9738
to_set = {}
9739
for param_set in params:
9740
for param in param_set:
9741
(_in, _out, value) = param
9742
to_set[_in] = value
9743
to_set[_out] = value
9744
self.set_parameters(to_set)
9745
self.start_subtest("Zeroing Mag OFS parameters with Mavlink")
9746
self.zero_mag_offset_parameters()
9747
self.progress("=========================================")
9748
# Change the default value to unexpected 42
9749
self.forty_two_mag_dia_odi_parameters()
9750
self.progress("Zeroing Mags orientations")
9751
self.set_parameter("COMPASS_ORIENT", 0)
9752
for count in range(2, compass_count + 1):
9753
self.set_parameter("COMPASS_ORIENT%d" % count, 0)
9754
9755
# Only care about compass prearm
9756
self.set_parameter("ARMING_CHECK", 4)
9757
9758
#################################################
9759
def do_test_mag_cal(mavproxy, params, compass_tnumber):
9760
self.start_subtest("Try magcal and make it stop around 30%")
9761
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
9762
reset_pos_and_start_magcal(mavproxy, target_mask)
9763
tstart = self.get_sim_time()
9764
reached_pct = [0] * compass_tnumber
9765
tstop = None
9766
while True:
9767
if self.get_sim_time_cached() - tstart > timeout:
9768
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
9769
m = self.mav.recv_match(type='MAG_CAL_PROGRESS', blocking=True, timeout=5)
9770
if m is None:
9771
if tstop is not None:
9772
# wait 3 second to unsure that the calibration is well stopped
9773
if self.get_sim_time_cached() - tstop > 10:
9774
if reached_pct[0] > 33:
9775
raise NotAchievedException("Mag calibration didn't stop")
9776
else:
9777
break
9778
else:
9779
continue
9780
else:
9781
continue
9782
if m is not None:
9783
self.progress("Mag CAL progress: %s" % str(m))
9784
cid = m.compass_id
9785
new_pct = int(m.completion_pct)
9786
if new_pct != reached_pct[cid]:
9787
if new_pct < reached_pct[cid]:
9788
raise NotAchievedException("Mag calibration restart when it shouldn't")
9789
reached_pct[cid] = new_pct
9790
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
9791
if cid == 0 and 13 <= reached_pct[0] <= 15:
9792
self.progress("Request again to start calibration, it shouldn't restart from 0")
9793
self.run_cmd(
9794
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
9795
p1=target_mask,
9796
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
9797
timeout=20,
9798
)
9799
9800
if reached_pct[0] > 30:
9801
self.run_cmd(
9802
mavutil.mavlink.MAV_CMD_DO_CANCEL_MAG_CAL,
9803
p1=target_mask,
9804
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
9805
)
9806
if tstop is None:
9807
tstop = self.get_sim_time_cached()
9808
if tstop is not None:
9809
# wait 3 second to unsure that the calibration is well stopped
9810
if self.get_sim_time_cached() - tstop > 3:
9811
raise NotAchievedException("Mag calibration didn't stop")
9812
self.check_zero_mag_parameters(params)
9813
self.check_zeros_mag_orient()
9814
9815
#################################################
9816
self.start_subtest("Try magcal and make it failed")
9817
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
9818
old_cal_fit = self.get_parameter("COMPASS_CAL_FIT")
9819
self.set_parameter("COMPASS_CAL_FIT", 0.001, add_to_context=False)
9820
reset_pos_and_start_magcal(mavproxy, target_mask)
9821
tstart = self.get_sim_time()
9822
reached_pct = [0] * compass_tnumber
9823
report_get = [0] * compass_tnumber
9824
while True:
9825
if self.get_sim_time_cached() - tstart > timeout:
9826
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
9827
m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=10)
9828
if m.get_type() == "MAG_CAL_REPORT":
9829
if report_get[m.compass_id] == 0:
9830
self.progress("Report: %s" % str(m))
9831
if m.cal_status == mavutil.mavlink.MAG_CAL_FAILED:
9832
report_get[m.compass_id] = 1
9833
else:
9834
raise NotAchievedException("Mag calibration didn't failed")
9835
if all(ele >= 1 for ele in report_get):
9836
self.progress("All Mag report failure")
9837
break
9838
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
9839
self.progress("Mag CAL progress: %s" % str(m))
9840
cid = m.compass_id
9841
new_pct = int(m.completion_pct)
9842
if new_pct != reached_pct[cid]:
9843
reached_pct[cid] = new_pct
9844
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
9845
if cid == 0 and 49 <= reached_pct[0] <= 50:
9846
self.progress("Try arming during calibration, should failed")
9847
self.try_arm(False, "Compass calibration running")
9848
9849
self.check_zero_mag_parameters(params)
9850
self.check_zeros_mag_orient()
9851
self.set_parameter("COMPASS_CAL_FIT", old_cal_fit, add_to_context=False)
9852
9853
#################################################
9854
self.start_subtest("Try magcal and wait success")
9855
self.progress("Compass mask is %s" % "{0:b}".format(target_mask))
9856
reset_pos_and_start_magcal(mavproxy, target_mask)
9857
progress_count = [0] * compass_tnumber
9858
reached_pct = [0] * compass_tnumber
9859
report_get = [0] * compass_tnumber
9860
tstart = self.get_sim_time()
9861
while True:
9862
if self.get_sim_time_cached() - tstart > timeout:
9863
raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS")
9864
m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=5)
9865
if m.get_type() == "MAG_CAL_REPORT":
9866
if report_get[m.compass_id] == 0:
9867
self.progress("Report: %s" % self.dump_message_verbose(m))
9868
param_names = ["SIM_MAG1_ORIENT"]
9869
for i in range(2, compass_tnumber+1):
9870
param_names.append("SIM_MAG%u_ORIENT" % i)
9871
for param_name in param_names:
9872
self.progress("%s=%f" % (param_name, self.get_parameter(param_name)))
9873
if m.cal_status == mavutil.mavlink.MAG_CAL_SUCCESS:
9874
threshold = 95
9875
if reached_pct[m.compass_id] < threshold:
9876
raise NotAchievedException(
9877
"Mag calibration report SUCCESS without >=%f%% completion (got %f%%)" %
9878
(threshold, reached_pct[m.compass_id]))
9879
report_get[m.compass_id] = 1
9880
else:
9881
raise NotAchievedException(
9882
"Mag calibration didn't SUCCEED (cal_status=%u) (progress_count=%s)" %
9883
(m.cal_status, progress_count[m.compass_id],))
9884
if all(ele >= 1 for ele in report_get):
9885
self.progress("All Mag report SUCCESS")
9886
break
9887
if m is not None and m.get_type() == "MAG_CAL_PROGRESS":
9888
cid = m.compass_id
9889
new_pct = int(m.completion_pct)
9890
progress_count[cid] += 1
9891
if new_pct != reached_pct[cid]:
9892
reached_pct[cid] = new_pct
9893
self.progress("Calibration progress compass ID %d: %s%%" % (cid, str(reached_pct[cid])))
9894
mavproxy.send("sitl_stop\n")
9895
mavproxy.send("sitl_attitude 0 0 0\n")
9896
self.progress("Checking that value aren't changed without acceptation")
9897
self.check_zero_mag_parameters(params)
9898
self.check_zeros_mag_orient()
9899
self.progress("Send acceptation and check value")
9900
self.wait_heartbeat()
9901
self.run_cmd(
9902
mavutil.mavlink.MAV_CMD_DO_ACCEPT_MAG_CAL,
9903
p1=target_mask, # p1: mag_mask
9904
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
9905
timeout=20,
9906
)
9907
self.check_mag_parameters(params, compass_tnumber)
9908
self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG1_ORIENT")})
9909
for count in range(2, compass_tnumber + 1):
9910
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})
9911
self.try_arm(False, "Compass calibrated requires reboot")
9912
9913
# test buzzer/notify ?
9914
self.progress("Rebooting and making sure we could arm with these values")
9915
self.drain_mav()
9916
self.reboot_sitl()
9917
if False: # FIXME! This fails with compasses inconsistent!
9918
self.wait_ready_to_arm(timeout=60)
9919
self.progress("Setting manually the parameter for other sensor to avoid compass consistency error")
9920
for idx in range(compass_tnumber, compass_count, 1):
9921
for param in params[idx]:
9922
(_in, _out, value) = param
9923
self.set_parameter(_out, value)
9924
for count in range(compass_tnumber + 1, compass_count + 1):
9925
self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))
9926
self.arm_vehicle()
9927
self.progress("Test calibration rejection when armed")
9928
self.run_cmd(
9929
mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
9930
p1=target_mask, # p1: mag_mask
9931
p2=0, # retry
9932
p3=0, # autosave
9933
p4=0, # delay
9934
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
9935
timeout=20,
9936
)
9937
self.disarm_vehicle()
9938
self.mavproxy_unload_module(mavproxy, "relay")
9939
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
9940
9941
ex = None
9942
9943
mavproxy = self.start_mavproxy()
9944
try:
9945
self.set_parameter("AHRS_EKF_TYPE", 10)
9946
self.set_parameter("SIM_GND_BEHAV", 0)
9947
9948
curr_params = []
9949
target_mask = 0
9950
# we test all bitmask plus 0 for all
9951
for run in range(-1, compass_count, 1):
9952
ntest_compass = compass_count
9953
if run < 0:
9954
# use bitmask 0 for all compass
9955
target_mask = 0
9956
else:
9957
target_mask |= (1 << run)
9958
ntest_compass = run + 1
9959
do_prep_mag_cal_test(mavproxy, curr_params)
9960
do_test_mag_cal(mavproxy, curr_params, ntest_compass)
9961
9962
except Exception as e:
9963
self.progress("Caught exception: %s" %
9964
self.get_exception_stacktrace(e))
9965
ex = e
9966
self.mavproxy_unload_module(mavproxy, "relay")
9967
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
9968
if ex is not None:
9969
raise ex
9970
9971
self.stop_mavproxy(mavproxy)
9972
9973
# need to reboot SITL after moving away from EKF type 10; we
9974
# can end up with home set but origin not and that will lead
9975
# to bad things.
9976
self.reboot_sitl()
9977
9978
def test_mag_reordering_assert_mag_transform(self, values, transforms):
9979
'''transforms ought to be read as, "take all the parameter values from
9980
the first compass parameters and shove them into the second indicating
9981
compass parameters'''
9982
9983
# create a set of mappings from one parameter name to another
9984
# e.g. COMPASS_OFS_X => COMPASS_OFS2_X if the transform is
9985
# [(1,2)]. [(1,2),(2,1)] should swap the compass values
9986
9987
parameter_mappings = {}
9988
for key in values.keys():
9989
parameter_mappings[key] = key
9990
for (old_compass_num, new_compass_num) in transforms:
9991
old_key_compass_bit = str(old_compass_num)
9992
if old_key_compass_bit == "1":
9993
old_key_compass_bit = ""
9994
new_key_compass_bit = str(new_compass_num)
9995
if new_key_compass_bit == "1":
9996
new_key_compass_bit = ""
9997
# vectors first:
9998
for key_vector_bit in ["OFS", "DIA", "ODI", "MOT"]:
9999
for axis in "X", "Y", "Z":
10000
old_key = "COMPASS_%s%s_%s" % (key_vector_bit,
10001
old_key_compass_bit,
10002
axis)
10003
new_key = "COMPASS_%s%s_%s" % (key_vector_bit,
10004
new_key_compass_bit,
10005
axis)
10006
parameter_mappings[old_key] = new_key
10007
# then non-vectorey bits:
10008
for key_bit in "SCALE", "ORIENT":
10009
old_key = "COMPASS_%s%s" % (key_bit, old_key_compass_bit)
10010
new_key = "COMPASS_%s%s" % (key_bit, new_key_compass_bit)
10011
parameter_mappings[old_key] = new_key
10012
# then a sore thumb:
10013
if old_key_compass_bit == "":
10014
old_key = "COMPASS_EXTERNAL"
10015
else:
10016
old_key = "COMPASS_EXTERN%s" % old_key_compass_bit
10017
if new_key_compass_bit == "":
10018
new_key = "COMPASS_EXTERNAL"
10019
else:
10020
new_key = "COMPASS_EXTERN%s" % new_key_compass_bit
10021
parameter_mappings[old_key] = new_key
10022
10023
for key in values.keys():
10024
newkey = parameter_mappings[key]
10025
current_value = self.get_parameter(newkey)
10026
expected_value = values[key]
10027
if abs(current_value - expected_value) > 0.001:
10028
raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" %
10029
(newkey, expected_value, current_value, str(transforms), key))
10030
10031
def CompassReordering(self):
10032
'''Test Compass reordering when priorities are changed'''
10033
self.context_push()
10034
ex = None
10035
try:
10036
originals = {
10037
"COMPASS_OFS_X": 1.1,
10038
"COMPASS_OFS_Y": 1.2,
10039
"COMPASS_OFS_Z": 1.3,
10040
"COMPASS_DIA_X": 1.4,
10041
"COMPASS_DIA_Y": 1.5,
10042
"COMPASS_DIA_Z": 1.6,
10043
"COMPASS_ODI_X": 1.7,
10044
"COMPASS_ODI_Y": 1.8,
10045
"COMPASS_ODI_Z": 1.9,
10046
"COMPASS_MOT_X": 1.91,
10047
"COMPASS_MOT_Y": 1.92,
10048
"COMPASS_MOT_Z": 1.93,
10049
"COMPASS_SCALE": 1.94,
10050
"COMPASS_ORIENT": 1,
10051
"COMPASS_EXTERNAL": 2,
10052
10053
"COMPASS_OFS2_X": 2.1,
10054
"COMPASS_OFS2_Y": 2.2,
10055
"COMPASS_OFS2_Z": 2.3,
10056
"COMPASS_DIA2_X": 2.4,
10057
"COMPASS_DIA2_Y": 2.5,
10058
"COMPASS_DIA2_Z": 2.6,
10059
"COMPASS_ODI2_X": 2.7,
10060
"COMPASS_ODI2_Y": 2.8,
10061
"COMPASS_ODI2_Z": 2.9,
10062
"COMPASS_MOT2_X": 2.91,
10063
"COMPASS_MOT2_Y": 2.92,
10064
"COMPASS_MOT2_Z": 2.93,
10065
"COMPASS_SCALE2": 2.94,
10066
"COMPASS_ORIENT2": 3,
10067
"COMPASS_EXTERN2": 4,
10068
10069
"COMPASS_OFS3_X": 3.1,
10070
"COMPASS_OFS3_Y": 3.2,
10071
"COMPASS_OFS3_Z": 3.3,
10072
"COMPASS_DIA3_X": 3.4,
10073
"COMPASS_DIA3_Y": 3.5,
10074
"COMPASS_DIA3_Z": 3.6,
10075
"COMPASS_ODI3_X": 3.7,
10076
"COMPASS_ODI3_Y": 3.8,
10077
"COMPASS_ODI3_Z": 3.9,
10078
"COMPASS_MOT3_X": 3.91,
10079
"COMPASS_MOT3_Y": 3.92,
10080
"COMPASS_MOT3_Z": 3.93,
10081
"COMPASS_SCALE3": 3.94,
10082
"COMPASS_ORIENT3": 5,
10083
"COMPASS_EXTERN3": 6,
10084
}
10085
10086
# quick sanity check to ensure all values are unique:
10087
if len(originals.values()) != len(set(originals.values())):
10088
raise NotAchievedException("Values are not all unique!")
10089
10090
self.progress("Setting parameters")
10091
self.set_parameters(originals)
10092
10093
self.reboot_sitl()
10094
10095
# no transforms means our originals should be our finals:
10096
self.test_mag_reordering_assert_mag_transform(originals, [])
10097
10098
self.start_subtest("Pushing 1st mag to 3rd")
10099
ey = None
10100
self.context_push()
10101
try:
10102
# now try reprioritising compass 1 to be higher than compass 0:
10103
prio1_id = self.get_parameter("COMPASS_PRIO1_ID")
10104
prio2_id = self.get_parameter("COMPASS_PRIO2_ID")
10105
prio3_id = self.get_parameter("COMPASS_PRIO3_ID")
10106
self.set_parameter("COMPASS_PRIO1_ID", prio2_id)
10107
self.set_parameter("COMPASS_PRIO2_ID", prio3_id)
10108
self.set_parameter("COMPASS_PRIO3_ID", prio1_id)
10109
10110
self.reboot_sitl()
10111
10112
self.test_mag_reordering_assert_mag_transform(originals, [(2, 1),
10113
(3, 2),
10114
(1, 3)])
10115
10116
except Exception as e:
10117
self.progress("Caught exception: %s" %
10118
self.get_exception_stacktrace(e))
10119
ey = e
10120
self.context_pop()
10121
self.reboot_sitl()
10122
if ey is not None:
10123
raise ey
10124
10125
except Exception as e:
10126
self.progress("Caught exception: %s" %
10127
self.get_exception_stacktrace(e))
10128
ex = e
10129
self.context_pop()
10130
self.reboot_sitl()
10131
if ex is not None:
10132
raise ex
10133
10134
# something about SITLCompassCalibration appears to fail
10135
# this one, so we put it first:
10136
def FixedYawCalibration(self):
10137
'''Test Fixed Yaw Calibration'''
10138
self.context_push()
10139
ex = None
10140
try:
10141
MAG_OFS_X = 100
10142
MAG_OFS_Y = 200
10143
MAG_OFS_Z = 300
10144
wanted = {
10145
"COMPASS_OFS_X": (MAG_OFS_X, 3.0),
10146
"COMPASS_OFS_Y": (MAG_OFS_Y, 3.0),
10147
"COMPASS_OFS_Z": (MAG_OFS_Z, 3.0),
10148
"COMPASS_DIA_X": 1,
10149
"COMPASS_DIA_Y": 1,
10150
"COMPASS_DIA_Z": 1,
10151
"COMPASS_ODI_X": 0,
10152
"COMPASS_ODI_Y": 0,
10153
"COMPASS_ODI_Z": 0,
10154
10155
"COMPASS_OFS2_X": (MAG_OFS_X, 3.0),
10156
"COMPASS_OFS2_Y": (MAG_OFS_Y, 3.0),
10157
"COMPASS_OFS2_Z": (MAG_OFS_Z, 3.0),
10158
"COMPASS_DIA2_X": 1,
10159
"COMPASS_DIA2_Y": 1,
10160
"COMPASS_DIA2_Z": 1,
10161
"COMPASS_ODI2_X": 0,
10162
"COMPASS_ODI2_Y": 0,
10163
"COMPASS_ODI2_Z": 0,
10164
10165
"COMPASS_OFS3_X": (MAG_OFS_X, 3.0),
10166
"COMPASS_OFS3_Y": (MAG_OFS_Y, 3.0),
10167
"COMPASS_OFS3_Z": (MAG_OFS_Z, 3.0),
10168
"COMPASS_DIA3_X": 1,
10169
"COMPASS_DIA3_Y": 1,
10170
"COMPASS_DIA3_Z": 1,
10171
"COMPASS_ODI3_X": 0,
10172
"COMPASS_ODI3_Y": 0,
10173
"COMPASS_ODI3_Z": 0,
10174
}
10175
self.set_parameters({
10176
"SIM_MAG1_OFS_X": MAG_OFS_X,
10177
"SIM_MAG1_OFS_Y": MAG_OFS_Y,
10178
"SIM_MAG1_OFS_Z": MAG_OFS_Z,
10179
10180
"SIM_MAG2_OFS_X": MAG_OFS_X,
10181
"SIM_MAG2_OFS_Y": MAG_OFS_Y,
10182
"SIM_MAG2_OFS_Z": MAG_OFS_Z,
10183
10184
"SIM_MAG3_OFS_X": MAG_OFS_X,
10185
"SIM_MAG3_OFS_Y": MAG_OFS_Y,
10186
"SIM_MAG3_OFS_Z": MAG_OFS_Z,
10187
})
10188
10189
# set to some sensible-ish initial values. If your initial
10190
# offsets are way, way off you can get some very odd effects.
10191
for param in wanted:
10192
value = 0.0
10193
if "DIA" in param:
10194
value = 1.001
10195
elif "ODI" in param:
10196
value = 0.001
10197
self.set_parameter(param, value)
10198
10199
self.zero_mag_offset_parameters()
10200
10201
# wait until we definitely know where we are:
10202
self.poll_home_position(timeout=120)
10203
10204
ss = self.assert_receive_message('SIMSTATE', timeout=1, verbose=True)
10205
10206
self.run_cmd(
10207
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
10208
p1=math.degrees(ss.yaw),
10209
)
10210
self.verify_parameter_values(wanted)
10211
10212
# run same command but as command_int:
10213
self.zero_mag_offset_parameters()
10214
self.run_cmd_int(
10215
mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW,
10216
p1=math.degrees(ss.yaw),
10217
)
10218
self.verify_parameter_values(wanted)
10219
10220
self.progress("Rebooting and making sure we could arm with these values")
10221
self.reboot_sitl()
10222
self.wait_ready_to_arm(timeout=60)
10223
10224
except Exception as e:
10225
ex = e
10226
10227
self.context_pop()
10228
10229
if ex is not None:
10230
raise ex
10231
10232
def DataFlashOverMAVLink(self):
10233
'''Test DataFlash over MAVLink'''
10234
self.context_push()
10235
ex = None
10236
mavproxy = self.start_mavproxy()
10237
try:
10238
self.set_parameter("LOG_BACKEND_TYPE", 2)
10239
self.reboot_sitl()
10240
self.wait_ready_to_arm(check_prearm_bit=False)
10241
mavproxy.send('arm throttle\n')
10242
mavproxy.expect('PreArm: Logging failed')
10243
self.mavproxy_load_module(mavproxy, 'dataflash_logger')
10244
mavproxy.send("dataflash_logger set verbose 1\n")
10245
mavproxy.expect('logging started')
10246
mavproxy.send("dataflash_logger set verbose 0\n")
10247
self.delay_sim_time(1)
10248
self.do_timesync_roundtrip() # drain COMMAND_ACK from that failed arm
10249
self.arm_vehicle()
10250
tstart = self.get_sim_time()
10251
last_status = 0
10252
mavproxy.send('repeat add 1 dataflash_logger status\n')
10253
while True:
10254
now = self.get_sim_time()
10255
if now - tstart > 60:
10256
break
10257
if now - last_status > 5:
10258
last_status = now
10259
# seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:0
10260
mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")
10261
rate = float(mavproxy.match.group(1))
10262
self.progress("Rate: %f" % rate)
10263
desired_rate = 50
10264
if self.valgrind or self.callgrind:
10265
desired_rate /= 10
10266
if rate < desired_rate:
10267
raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))
10268
self.disarm_vehicle()
10269
mavproxy.send('repeat remove 0\n')
10270
except Exception as e:
10271
self.print_exception_caught(e)
10272
self.disarm_vehicle()
10273
ex = e
10274
self.mavproxy_unload_module(mavproxy, 'dataflash_logger')
10275
10276
# the following things won't work - but they shouldn't die either:
10277
self.mavproxy_load_module(mavproxy, 'log')
10278
10279
self.progress("Try log list")
10280
mavproxy.send("log list\n")
10281
mavproxy.expect("No logs")
10282
10283
self.progress("Try log erase")
10284
mavproxy.send("log erase\n")
10285
# no response to this...
10286
10287
self.progress("Try log download")
10288
mavproxy.send("log download 1\n")
10289
# no response to this...
10290
10291
self.mavproxy_unload_module(mavproxy, 'log')
10292
10293
self.context_pop()
10294
10295
self.stop_mavproxy(mavproxy)
10296
self.reboot_sitl()
10297
if ex is not None:
10298
raise ex
10299
10300
def DataFlash(self):
10301
"""Test DataFlash SITL backend"""
10302
self.context_push()
10303
ex = None
10304
mavproxy = self.start_mavproxy()
10305
try:
10306
self.set_parameter("LOG_BACKEND_TYPE", 4)
10307
self.set_parameter("LOG_FILE_DSRMROT", 1)
10308
self.set_parameter("LOG_BLK_RATEMAX", 1)
10309
self.reboot_sitl()
10310
# First log created here, but we are in chip erase so ignored
10311
mavproxy.send("module load log\n")
10312
mavproxy.send("log erase\n")
10313
mavproxy.expect("Chip erase complete")
10314
10315
self.wait_ready_to_arm()
10316
if self.is_copter() or self.is_plane():
10317
self.set_autodisarm_delay(0)
10318
self.arm_vehicle()
10319
self.delay_sim_time(5)
10320
self.disarm_vehicle()
10321
# First log created here
10322
self.delay_sim_time(2)
10323
self.arm_vehicle()
10324
self.delay_sim_time(5)
10325
self.disarm_vehicle()
10326
# Second log created here
10327
self.delay_sim_time(2)
10328
mavproxy.send("log list\n")
10329
mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
10330
log_num = int(mavproxy.match.group(1))
10331
numlogs = int(mavproxy.match.group(2))
10332
lastlog = int(mavproxy.match.group(3))
10333
size = int(mavproxy.match.group(4))
10334
if numlogs != 2 or log_num != 1 or size <= 0:
10335
raise NotAchievedException("Unexpected log information %d %d %d" % (log_num, numlogs, lastlog))
10336
self.progress("Log size: %d" % size)
10337
self.reboot_sitl()
10338
# This starts a new log with a time of 0, wait for arm so that we can insert the correct time
10339
self.wait_ready_to_arm()
10340
# Third log created here
10341
mavproxy.send("log list\n")
10342
mavproxy.expect("Log 1 numLogs 3 lastLog 3 size")
10343
10344
# Download second and third logs
10345
mavproxy.send("log download 2 logs/dataflash-log-002.BIN\n")
10346
mavproxy.expect("Finished downloading", timeout=120)
10347
mavproxy.send("log download 3 logs/dataflash-log-003.BIN\n")
10348
mavproxy.expect("Finished downloading", timeout=120)
10349
10350
# Erase the logs
10351
mavproxy.send("log erase\n")
10352
mavproxy.expect("Chip erase complete")
10353
10354
except Exception as e:
10355
self.print_exception_caught(e)
10356
ex = e
10357
mavproxy.send("module unload log\n")
10358
self.stop_mavproxy(mavproxy)
10359
self.context_pop()
10360
self.reboot_sitl()
10361
if ex is not None:
10362
raise ex
10363
10364
def validate_log_file(self, logname, header_errors=0):
10365
"""Validate the contents of a log file"""
10366
# read the downloaded log - it must parse without error
10367
class Capturing(list):
10368
def __enter__(self):
10369
self._stderr = sys.stderr
10370
sys.stderr = self._stringio = StringIO.StringIO()
10371
return self
10372
10373
def __exit__(self, *args):
10374
self.extend(self._stringio.getvalue().splitlines())
10375
del self._stringio # free up some memory
10376
sys.stderr = self._stderr
10377
10378
with Capturing() as df_output:
10379
try:
10380
mlog = mavutil.mavlink_connection(logname)
10381
while True:
10382
m = mlog.recv_match()
10383
if m is None:
10384
break
10385
except Exception as e:
10386
raise NotAchievedException("Error reading log file %s: %s" % (logname, str(e)))
10387
10388
herrors = 0
10389
10390
for msg in df_output:
10391
if msg.startswith("bad header") or msg.startswith("unknown msg type"):
10392
herrors = herrors + 1
10393
10394
if herrors > header_errors:
10395
raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors))
10396
10397
def DataFlashErase(self):
10398
"""Test that erasing the dataflash chip and creating a new log is error free"""
10399
mavproxy = self.start_mavproxy()
10400
10401
ex = None
10402
self.context_push()
10403
try:
10404
self.set_parameter("LOG_BACKEND_TYPE", 4)
10405
self.reboot_sitl()
10406
mavproxy.send("module load log\n")
10407
mavproxy.send("log erase\n")
10408
mavproxy.expect("Chip erase complete")
10409
self.set_parameter("LOG_DISARMED", 1)
10410
self.delay_sim_time(3)
10411
self.set_parameter("LOG_DISARMED", 0)
10412
mavproxy.send("log download 1 logs/dataflash-log-erase.BIN\n")
10413
mavproxy.expect("Finished downloading", timeout=120)
10414
# read the downloaded log - it must parse without error
10415
self.validate_log_file("logs/dataflash-log-erase.BIN")
10416
10417
self.start_subtest("Test file wrapping results in a valid file")
10418
# roughly 4mb
10419
self.set_parameter("LOG_FILE_DSRMROT", 1)
10420
self.set_parameter("LOG_BITMASK", 131071)
10421
self.wait_ready_to_arm()
10422
if self.is_copter() or self.is_plane():
10423
self.set_autodisarm_delay(0)
10424
self.arm_vehicle()
10425
self.delay_sim_time(30)
10426
self.disarm_vehicle()
10427
# roughly 4mb
10428
self.arm_vehicle()
10429
self.delay_sim_time(30)
10430
self.disarm_vehicle()
10431
# roughly 9mb, should wrap around
10432
self.arm_vehicle()
10433
self.delay_sim_time(50)
10434
self.disarm_vehicle()
10435
# make sure we have finished logging
10436
self.delay_sim_time(15)
10437
mavproxy.send("log list\n")
10438
try:
10439
mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
10440
except pexpect.TIMEOUT as e:
10441
if self.sitl_is_running():
10442
self.progress("SITL is running")
10443
else:
10444
self.progress("SITL is NOT running")
10445
raise NotAchievedException("Received %s" % str(e))
10446
if int(mavproxy.match.group(2)) != 3:
10447
raise NotAchievedException("Expected 3 logs got %s" % (mavproxy.match.group(2)))
10448
10449
mavproxy.send("log download 1 logs/dataflash-log-erase2.BIN\n")
10450
mavproxy.expect("Finished downloading", timeout=120)
10451
self.validate_log_file("logs/dataflash-log-erase2.BIN", 1)
10452
10453
mavproxy.send("log download latest logs/dataflash-log-erase3.BIN\n")
10454
mavproxy.expect("Finished downloading", timeout=120)
10455
self.validate_log_file("logs/dataflash-log-erase3.BIN", 1)
10456
10457
# clean up
10458
mavproxy.send("log erase\n")
10459
mavproxy.expect("Chip erase complete")
10460
10461
# clean up
10462
mavproxy.send("log erase\n")
10463
mavproxy.expect("Chip erase complete")
10464
10465
except Exception as e:
10466
self.print_exception_caught(e)
10467
ex = e
10468
10469
mavproxy.send("module unload log\n")
10470
10471
self.context_pop()
10472
self.reboot_sitl()
10473
10474
self.stop_mavproxy(mavproxy)
10475
10476
if ex is not None:
10477
raise ex
10478
10479
def ArmFeatures(self):
10480
'''Arm features'''
10481
# TEST ARMING/DISARM
10482
self.delay_sim_time(12) # wait for gyros/accels to be happy
10483
if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub():
10484
raise ValueError("Arming check should be 1")
10485
if not self.is_sub() and not self.is_tracker():
10486
self.set_parameter("ARMING_RUDDER", 2) # allow arm and disarm with rudder on first tests
10487
if self.is_copter():
10488
interlock_channel = 8 # Plane got flighmode_ch on channel 8
10489
if not self.is_heli(): # heli don't need interlock option
10490
interlock_channel = 9
10491
self.set_parameter("RC%u_OPTION" % interlock_channel, 32)
10492
self.set_rc(interlock_channel, 1000)
10493
self.zero_throttle()
10494
# Disable auto disarm for next tests
10495
# Rover and Sub don't have auto disarm
10496
if self.is_copter() or self.is_plane():
10497
self.set_autodisarm_delay(0)
10498
self.start_subtest("Test normal arm and disarm features")
10499
self.wait_ready_to_arm()
10500
self.progress("default arm_vehicle() call")
10501
if not self.arm_vehicle():
10502
raise NotAchievedException("Failed to ARM")
10503
self.progress("default disarm_vehicle() call")
10504
self.disarm_vehicle()
10505
10506
self.start_subtest("Arm/disarm vehicle with COMMAND_INT")
10507
self.run_cmd_int(
10508
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10509
p1=1, # ARM
10510
)
10511
self.run_cmd_int(
10512
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10513
p1=0, # DISARM
10514
)
10515
10516
self.progress("arm with mavproxy")
10517
mavproxy = self.start_mavproxy()
10518
if not self.mavproxy_arm_vehicle(mavproxy):
10519
raise NotAchievedException("Failed to ARM")
10520
self.progress("disarm with mavproxy")
10521
self.mavproxy_disarm_vehicle(mavproxy)
10522
self.stop_mavproxy(mavproxy)
10523
10524
if not self.is_sub():
10525
self.start_subtest("Test arm with rc input")
10526
self.arm_motors_with_rc_input()
10527
self.progress("disarm with rc input")
10528
if self.is_balancebot():
10529
self.progress("balancebot can't disarm with RC input")
10530
self.disarm_vehicle()
10531
else:
10532
self.disarm_motors_with_rc_input()
10533
10534
self.start_subtest("Test arm and disarm with switch")
10535
arming_switch = 7
10536
self.set_parameter("RC%d_OPTION" % arming_switch, 153)
10537
self.set_rc(arming_switch, 1000)
10538
# delay so a transition is seen by the RC switch code:
10539
self.delay_sim_time(0.5)
10540
self.arm_motors_with_switch(arming_switch)
10541
self.disarm_motors_with_switch(arming_switch)
10542
self.set_rc(arming_switch, 1000)
10543
10544
if self.is_copter():
10545
self.start_subtest("Test arming failure with throttle too high")
10546
self.set_rc(3, 1800)
10547
try:
10548
if self.arm_vehicle():
10549
raise NotAchievedException("Armed when throttle too high")
10550
except ValueError:
10551
pass
10552
try:
10553
self.arm_motors_with_rc_input()
10554
except NotAchievedException:
10555
pass
10556
if self.armed():
10557
raise NotAchievedException(
10558
"Armed via RC when throttle too high")
10559
try:
10560
self.arm_motors_with_switch(arming_switch)
10561
except NotAchievedException:
10562
pass
10563
if self.armed():
10564
raise NotAchievedException("Armed via RC when switch too high")
10565
self.zero_throttle()
10566
self.set_rc(arming_switch, 1000)
10567
10568
# Sub doesn't have 'stick commands'
10569
self.start_subtest("Test arming failure with ARMING_RUDDER=0")
10570
self.set_parameter("ARMING_RUDDER", 0)
10571
try:
10572
self.arm_motors_with_rc_input()
10573
except NotAchievedException:
10574
pass
10575
if self.armed():
10576
raise NotAchievedException(
10577
"Armed with rudder when ARMING_RUDDER=0")
10578
self.start_subtest("Test disarming failure with ARMING_RUDDER=0")
10579
self.arm_vehicle()
10580
try:
10581
self.disarm_motors_with_rc_input(watch_for_disabled=True)
10582
except NotAchievedException:
10583
pass
10584
if not self.armed():
10585
raise NotAchievedException(
10586
"Disarmed with rudder when ARMING_RUDDER=0")
10587
self.disarm_vehicle()
10588
self.wait_heartbeat()
10589
self.start_subtest("Test disarming failure with ARMING_RUDDER=1")
10590
self.set_parameter("ARMING_RUDDER", 1)
10591
self.arm_vehicle()
10592
try:
10593
self.disarm_motors_with_rc_input()
10594
except NotAchievedException:
10595
pass
10596
if not self.armed():
10597
raise NotAchievedException(
10598
"Disarmed with rudder with ARMING_RUDDER=1")
10599
self.disarm_vehicle()
10600
self.wait_heartbeat()
10601
self.set_parameter("ARMING_RUDDER", 2)
10602
10603
if self.is_copter():
10604
self.start_subtest("Test arming failure with interlock enabled")
10605
self.set_rc(interlock_channel, 2000)
10606
try:
10607
self.arm_motors_with_rc_input()
10608
except NotAchievedException:
10609
pass
10610
if self.armed():
10611
raise NotAchievedException(
10612
"Armed with RC input when interlock enabled")
10613
try:
10614
self.arm_motors_with_switch(arming_switch)
10615
except NotAchievedException:
10616
pass
10617
if self.armed():
10618
raise NotAchievedException("Armed with switch when interlock enabled")
10619
self.disarm_vehicle()
10620
self.wait_heartbeat()
10621
self.set_rc(arming_switch, 1000)
10622
self.set_rc(interlock_channel, 1000)
10623
if self.is_heli():
10624
self.start_subtest("Test motor interlock enable can't be set while disarmed")
10625
self.set_rc(interlock_channel, 2000)
10626
channel_field = "servo%u_raw" % interlock_channel
10627
interlock_value = self.get_parameter("SERVO%u_MIN" % interlock_channel)
10628
tstart = self.get_sim_time()
10629
while True:
10630
if self.get_sim_time_cached() - tstart > 20:
10631
self.set_rc(interlock_channel, 1000)
10632
break # success!
10633
m = self.mav.recv_match(type='SERVO_OUTPUT_RAW',
10634
blocking=True,
10635
timeout=2)
10636
if m is None:
10637
continue
10638
m_value = getattr(m, channel_field, None)
10639
if m_value is None:
10640
self.set_rc(interlock_channel, 1000)
10641
raise ValueError("Message has no %s field" %
10642
channel_field)
10643
self.progress("SERVO_OUTPUT_RAW.%s=%u want=%u" %
10644
(channel_field, m_value, interlock_value))
10645
if m_value != interlock_value:
10646
self.set_rc(interlock_channel, 1000)
10647
raise NotAchievedException("Motor interlock was changed while disarmed")
10648
self.set_rc(interlock_channel, 1000)
10649
10650
self.start_subtest("Test all mode arming")
10651
self.wait_ready_to_arm()
10652
10653
if self.arming_test_mission() is not None:
10654
self.load_mission(self.arming_test_mission())
10655
10656
for mode in self.mav.mode_mapping():
10657
self.drain_mav()
10658
self.start_subtest("Mode : %s" % mode)
10659
if mode == "FOLLOW":
10660
self.set_parameter("FOLL_ENABLE", 1)
10661
if mode in self.get_normal_armable_modes_list():
10662
self.progress("Armable mode : %s" % mode)
10663
self.change_mode(mode)
10664
self.arm_vehicle()
10665
self.disarm_vehicle()
10666
self.progress("PASS arm mode : %s" % mode)
10667
if mode in self.get_not_armable_mode_list():
10668
if mode in self.get_not_disarmed_settable_modes_list():
10669
self.progress("Not settable mode : %s" % mode)
10670
try:
10671
self.change_mode(mode, timeout=15)
10672
except AutoTestTimeoutException:
10673
self.progress("PASS not able to set mode : %s disarmed" % mode)
10674
except ValueError:
10675
self.progress("PASS not able to set mode : %s disarmed" % mode)
10676
else:
10677
self.progress("Not armable mode : %s" % mode)
10678
self.change_mode(mode)
10679
self.run_cmd(
10680
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10681
p1=1, # ARM
10682
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
10683
)
10684
self.progress("PASS not able to arm in mode : %s" % mode)
10685
if mode in self.get_position_armable_modes_list():
10686
self.progress("Armable mode needing Position : %s" % mode)
10687
self.wait_ekf_happy()
10688
self.change_mode(mode)
10689
self.arm_vehicle()
10690
self.wait_heartbeat()
10691
self.disarm_vehicle()
10692
self.progress("PASS arm mode : %s" % mode)
10693
self.progress("Not armable mode without Position : %s" % mode)
10694
self.wait_gps_disable()
10695
self.change_mode(mode)
10696
self.run_cmd(
10697
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
10698
p1=1, # ARM
10699
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
10700
)
10701
self.set_parameter("SIM_GPS1_ENABLE", 1)
10702
self.wait_ekf_happy() # EKF may stay unhappy for a while
10703
self.progress("PASS not able to arm without Position in mode : %s" % mode)
10704
if mode in self.get_no_position_not_settable_modes_list():
10705
self.progress("Setting mode need Position : %s" % mode)
10706
self.wait_ekf_happy()
10707
self.wait_gps_disable()
10708
try:
10709
self.change_mode(mode, timeout=15)
10710
except AutoTestTimeoutException:
10711
self.set_parameter("SIM_GPS1_ENABLE", 1)
10712
self.progress("PASS not able to set mode without Position : %s" % mode)
10713
except ValueError:
10714
self.set_parameter("SIM_GPS1_ENABLE", 1)
10715
self.progress("PASS not able to set mode without Position : %s" % mode)
10716
if mode == "FOLLOW":
10717
self.set_parameter("FOLL_ENABLE", 0)
10718
self.change_mode(self.default_mode())
10719
if self.armed():
10720
self.disarm_vehicle()
10721
10722
# we should find at least one Armed event and one disarmed
10723
# event, and at least one ARM message for arm and disarm
10724
wants = set([
10725
("Armed EV message", "EV", lambda e : e.Id == 10),
10726
("Disarmed EV message", "EV", lambda e : e.Id == 11),
10727
("Armed ARM message", "ARM", lambda a : a.ArmState == 1),
10728
("Disarmed ARM message", "ARM", lambda a : a.ArmState == 0),
10729
])
10730
10731
dfreader = self.dfreader_for_current_onboard_log()
10732
types = set()
10733
for (name, msgtype, l) in wants:
10734
types.add(msgtype)
10735
10736
while True:
10737
m = dfreader.recv_match(type=types)
10738
if m is None:
10739
break
10740
wantscopy = copy.copy(wants)
10741
for want in wantscopy:
10742
(name, msgtype, l) = want
10743
if m.get_type() != msgtype:
10744
continue
10745
if l(m):
10746
self.progress("Found %s" % name)
10747
wants.discard(want)
10748
if len(wants) == 0:
10749
break
10750
10751
if len(wants):
10752
msg = ", ".join([x[0] for x in wants])
10753
raise NotAchievedException("Did not find (%s)" % msg)
10754
10755
self.progress("ALL PASS")
10756
# TODO : Test arming magic;
10757
10758
def measure_message_rate(self, victim_message, timeout=10, mav=None):
10759
if mav is None:
10760
mav = self.mav
10761
tstart = self.get_sim_time()
10762
count = 0
10763
while self.get_sim_time_cached() < tstart + timeout:
10764
m = mav.recv_match(
10765
type=victim_message,
10766
blocking=True,
10767
timeout=0.1
10768
)
10769
if m is not None:
10770
count += 1
10771
if mav != self.mav:
10772
self.drain_mav(self.mav)
10773
10774
time_delta = self.get_sim_time_cached() - tstart
10775
self.progress("%s count after %f seconds: %u" %
10776
(victim_message, time_delta, count))
10777
return count/time_delta
10778
10779
def rate_to_interval_us(self, rate):
10780
return 1/float(rate)*1000000.0
10781
10782
def interval_us_to_rate(self, interval):
10783
if interval == 0:
10784
raise ValueError("Zero interval is infinite rate")
10785
return 1000000.0/float(interval)
10786
10787
def set_message_rate_hz(self, id, rate_hz, mav=None, run_cmd=None):
10788
'''set a message rate in Hz; 0 for original, -1 to disable'''
10789
if run_cmd is None:
10790
run_cmd = self.run_cmd
10791
if isinstance(id, str):
10792
id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id)
10793
if rate_hz == 0 or rate_hz == -1:
10794
set_interval = rate_hz
10795
else:
10796
set_interval = self.rate_to_interval_us(rate_hz)
10797
run_cmd(
10798
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
10799
p1=id,
10800
p2=set_interval,
10801
mav=mav,
10802
)
10803
10804
def get_message_rate_hz(self, id, mav=None, run_cmd=None):
10805
'''return rate message is being sent, in Hz'''
10806
if run_cmd is None:
10807
run_cmd = self.run_cmd
10808
10809
interval = self.get_message_interval(id, mav=mav, run_cmd=run_cmd)
10810
return self.interval_us_to_rate(interval)
10811
10812
def send_get_message_interval(self, victim_message, mav=None):
10813
if mav is None:
10814
mav = self.mav
10815
if isinstance(victim_message, str):
10816
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
10817
mav.mav.command_long_send(
10818
1,
10819
1,
10820
mavutil.mavlink.MAV_CMD_GET_MESSAGE_INTERVAL,
10821
1, # confirmation
10822
float(victim_message),
10823
0,
10824
0,
10825
0,
10826
0,
10827
0,
10828
0)
10829
10830
def get_message_interval(self, victim_message, mav=None, run_cmd=None):
10831
'''returns message interval in microseconds'''
10832
if run_cmd is None:
10833
run_cmd = self.run_cmd
10834
10835
self.send_get_message_interval(victim_message, mav=mav)
10836
m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=1, mav=mav)
10837
10838
if isinstance(victim_message, str):
10839
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
10840
if m.message_id != victim_message:
10841
raise NotAchievedException(f"Unexpected ID in MESSAGE_INTERVAL (want={victim_message}, got={m.message_id}")
10842
10843
return m.interval_us
10844
10845
def set_message_interval(self, victim_message, interval_us, mav=None):
10846
'''sets message interval in microseconds'''
10847
if isinstance(victim_message, str):
10848
victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message)
10849
self.run_cmd(
10850
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
10851
p1=victim_message,
10852
p2=interval_us,
10853
mav=mav,
10854
)
10855
10856
def test_rate(self,
10857
desc,
10858
in_rate,
10859
expected_rate
10860
, mav=None,
10861
victim_message="VFR_HUD",
10862
ndigits=0,
10863
message_rate_sample_period=10):
10864
if mav is None:
10865
mav = self.mav
10866
10867
self.progress("###### %s" % desc)
10868
self.progress("Setting rate to %f" % round(in_rate, ndigits=ndigits))
10869
10870
self.set_message_rate_hz(victim_message, in_rate, mav=mav)
10871
10872
new_measured_rate = self.measure_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav)
10873
self.progress(
10874
"Measured rate: %f (want %f)" %
10875
(round(new_measured_rate, ndigits=ndigits),
10876
round(expected_rate, ndigits=ndigits))
10877
)
10878
notachieved_ex = None
10879
if round(new_measured_rate, ndigits=ndigits) != round(expected_rate, ndigits=ndigits):
10880
notachieved_ex = NotAchievedException(
10881
"Rate not achieved (got %f want %f)" %
10882
(round(new_measured_rate, ndigits),
10883
round(expected_rate, ndigits)))
10884
10885
# make sure get_message_interval works:
10886
self.send_get_message_interval(victim_message, mav=mav)
10887
10888
m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=30, mav=mav)
10889
10890
if in_rate == 0:
10891
want = self.rate_to_interval_us(expected_rate)
10892
elif in_rate == -1:
10893
want = in_rate
10894
else:
10895
want = self.rate_to_interval_us(in_rate)
10896
10897
if m.interval_us != want:
10898
raise NotAchievedException("Did not read same interval back from autopilot: want=%d got=%d)" %
10899
(want, m.interval_us))
10900
m = self.assert_receive_message('COMMAND_ACK', mav=mav)
10901
if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED:
10902
raise NotAchievedException("Expected ACCEPTED for reading message interval")
10903
10904
if notachieved_ex is not None:
10905
raise notachieved_ex
10906
10907
def SET_MESSAGE_INTERVAL(self):
10908
'''Test MAV_CMD_SET_MESSAGE_INTERVAL'''
10909
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
10910
self.reboot_sitl() # needed for CAM1_TYPE to take effect
10911
self.start_subtest('Basic tests')
10912
self.test_set_message_interval_basic()
10913
self.start_subtest('Many-message tests')
10914
self.test_set_message_interval_many()
10915
10916
def MESSAGE_INTERVAL_COMMAND_INT(self):
10917
'''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT'''
10918
original_rate = round(self.measure_message_rate("VFR_HUD", 20))
10919
self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)
10920
if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1:
10921
raise NotAchievedException("Did not set rate")
10922
10923
# Try setting a rate well beyond SCHED_LOOP_RATE
10924
self.run_cmd(
10925
mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL,
10926
p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD,
10927
p2=self.rate_to_interval_us(800),
10928
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
10929
)
10930
10931
self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT")
10932
# 148 is AUTOPILOT_VERSION:
10933
self.context_collect('AUTOPILOT_VERSION')
10934
self.run_cmd_int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, 148)
10935
self.delay_sim_time(2)
10936
count = len(self.context_collection('AUTOPILOT_VERSION'))
10937
if count != 1:
10938
raise NotAchievedException(f"Did not get single AUTOPILOT_VERSION message (count={count}")
10939
10940
def test_set_message_interval_many(self):
10941
messages = [
10942
'CAMERA_FEEDBACK',
10943
'RAW_IMU',
10944
'ATTITUDE',
10945
]
10946
ex = None
10947
try:
10948
rate = 5
10949
for message in messages:
10950
self.set_message_rate_hz(message, rate)
10951
for message in messages:
10952
self.assert_message_rate_hz(message, rate)
10953
except Exception as e:
10954
self.print_exception_caught(e)
10955
ex = e
10956
10957
# reset message rates to default:
10958
for message in messages:
10959
self.set_message_rate_hz(message, -1)
10960
10961
if ex is not None:
10962
raise ex
10963
10964
def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0, mav=None):
10965
if mav is None:
10966
mav = self.mav
10967
self.drain_mav(mav)
10968
rate = round(self.measure_message_rate(message, sample_period, mav=mav), ndigits=ndigits)
10969
self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits)))
10970
if rate != want_rate:
10971
raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate))
10972
10973
def test_set_message_interval_basic(self):
10974
ex = None
10975
try:
10976
rate = round(self.measure_message_rate("VFR_HUD", 20))
10977
self.progress("Initial rate: %u" % rate)
10978
10979
self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD")
10980
# this assumes the streamrates have not been played with:
10981
self.test_rate("Resetting original rate using 0-value", 0, rate)
10982
self.test_rate("Disabling using -1-value", -1, 0)
10983
self.test_rate("Resetting original rate", 0, rate)
10984
10985
self.progress("try getting a message which is not ordinarily streamed out")
10986
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))
10987
if rate != 0:
10988
raise PreconditionFailedException("Already getting CAMERA_FEEDBACK")
10989
self.progress("try various message rates")
10990
for want_rate in range(5, 14):
10991
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,
10992
want_rate)
10993
self.assert_message_rate_hz('CAMERA_FEEDBACK', want_rate)
10994
10995
self.progress("try at the main loop rate")
10996
# have to reset the speedup as MAVProxy can't keep up otherwise
10997
old_speedup = self.get_parameter("SIM_SPEEDUP")
10998
self.set_parameter("SIM_SPEEDUP", 1.0)
10999
# ArduPilot currently limits message rate to 80% of main loop rate:
11000
want_rate = self.get_parameter("SCHED_LOOP_RATE") * 0.8
11001
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,
11002
want_rate)
11003
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20))
11004
self.set_parameter("SIM_SPEEDUP", old_speedup)
11005
self.progress("Want=%f got=%f" % (want_rate, rate))
11006
if abs(rate - want_rate) > 2:
11007
raise NotAchievedException("Did not get expected rate")
11008
11009
self.drain_mav()
11010
11011
non_existant_id = 145
11012
self.send_get_message_interval(non_existant_id)
11013
m = self.assert_receive_message('MESSAGE_INTERVAL')
11014
if m.interval_us != 0:
11015
raise NotAchievedException("Supposed to get 0 back for unsupported stream")
11016
m = self.assert_receive_message('COMMAND_ACK')
11017
if m.result != mavutil.mavlink.MAV_RESULT_FAILED:
11018
raise NotAchievedException("Getting rate of unsupported message is a failure")
11019
11020
except Exception as e:
11021
self.print_exception_caught(e)
11022
ex = e
11023
11024
self.progress("Resetting CAMERA_FEEDBACK rate to default rate")
11025
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, 0)
11026
self.assert_message_rate_hz('CAMERA_FEEDBACK', 0)
11027
11028
if ex is not None:
11029
raise ex
11030
11031
def send_poll_message(self, message_id, target_sysid=None, target_compid=None, quiet=False, mav=None):
11032
if mav is None:
11033
mav = self.mav
11034
if isinstance(message_id, str):
11035
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
11036
self.send_cmd(
11037
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
11038
p1=message_id,
11039
target_sysid=target_sysid,
11040
target_compid=target_compid,
11041
quiet=quiet,
11042
mav=mav,
11043
)
11044
11045
def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None):
11046
if mav is None:
11047
mav = self.mav
11048
if target_sysid is None:
11049
target_sysid = self.sysid_thismav()
11050
if target_compid is None:
11051
target_compid = 1
11052
if isinstance(message_id, str):
11053
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
11054
tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work
11055
self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid)
11056
self.run_cmd_get_ack(
11057
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
11058
mavutil.mavlink.MAV_RESULT_ACCEPTED,
11059
timeout,
11060
quiet=quiet,
11061
mav=mav,
11062
)
11063
while True:
11064
if self.get_sim_time_cached() - tstart > timeout:
11065
raise NotAchievedException("Did not receive polled message")
11066
m = mav.recv_match(blocking=True,
11067
timeout=0.1)
11068
if self.mav != mav:
11069
self.drain_mav()
11070
if m is None:
11071
continue
11072
if m.id != message_id:
11073
continue
11074
if (m.get_srcSystem() != target_sysid or
11075
m.get_srcComponent() != target_compid):
11076
continue
11077
return m
11078
11079
def get_messages_frame(self, msg_names):
11080
'''try to get a "frame" of named messages - a set of messages as close
11081
in time as possible'''
11082
msgs = {}
11083
11084
def get_msgs(mav, m):
11085
t = m.get_type()
11086
if t in msg_names:
11087
msgs[t] = m
11088
self.do_timesync_roundtrip()
11089
self.install_message_hook(get_msgs)
11090
for msg_name in msg_names:
11091
self.send_poll_message(msg_name)
11092
while True:
11093
self.mav.recv_match(blocking=True)
11094
if len(msgs.keys()) == len(msg_names):
11095
break
11096
11097
self.remove_message_hook(get_msgs)
11098
11099
return msgs
11100
11101
def REQUEST_MESSAGE(self, timeout=60):
11102
'''Test MAV_CMD_REQUEST_MESSAGE'''
11103
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
11104
self.reboot_sitl() # needed for CAM1_TYPE to take effect
11105
rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 10))
11106
if rate != 0:
11107
raise PreconditionFailedException("Receiving camera feedback")
11108
self.poll_message("CAMERA_FEEDBACK")
11109
11110
def clear_mission(self, mission_type, target_system=1, target_component=1):
11111
'''clear mision_type from autopilot. Note that this does NOT actually
11112
send a MISSION_CLEAR_ALL message
11113
'''
11114
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_ALL:
11115
# recurse
11116
if not self.is_tracker() and not self.is_blimp():
11117
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
11118
if not self.is_blimp():
11119
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
11120
if not self.is_sub() and not self.is_tracker() and not self.is_blimp():
11121
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
11122
self.last_wp_load = time.time()
11123
return
11124
11125
self.mav.mav.mission_count_send(target_system,
11126
target_component,
11127
0,
11128
mission_type)
11129
self.assert_received_message_field_values('MISSION_ACK', {
11130
"target_system": self.mav.mav.srcSystem,
11131
"target_component": self.mav.mav.srcComponent,
11132
"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,
11133
})
11134
11135
if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION:
11136
self.last_wp_load = time.time()
11137
11138
def clear_fence_using_mavproxy(self, mavproxy, timeout=10):
11139
mavproxy.send("fence clear\n")
11140
tstart = self.get_sim_time_cached()
11141
while True:
11142
now = self.get_sim_time_cached()
11143
if now - tstart > timeout:
11144
raise AutoTestTimeoutException("FENCE_TOTAL did not go to zero")
11145
if self.get_parameter("FENCE_TOTAL") == 0:
11146
break
11147
11148
def clear_fence(self):
11149
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
11150
11151
# Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa
11152
def ConfigErrorLoop(self):
11153
'''test the sensor config error loop works and that parameter sets are persistent'''
11154
parameter_name = "SERVO8_MIN"
11155
old_parameter_value = self.get_parameter(parameter_name)
11156
old_sim_baro_count = self.get_parameter("SIM_BARO_COUNT")
11157
new_parameter_value = old_parameter_value + 5
11158
ex = None
11159
try:
11160
self.set_parameter("STAT_BOOTCNT", 0)
11161
self.set_parameter("SIM_BARO_COUNT", -1)
11162
11163
if self.is_tracker():
11164
# starts armed...
11165
self.progress("Disarming tracker")
11166
self.disarm_vehicle(force=True)
11167
11168
self.reboot_sitl(required_bootcount=1)
11169
self.progress("Waiting for 'Config error'")
11170
# SYSTEM_TIME not sent in config error loop:
11171
self.wait_statustext("Config error", wallclock_timeout=True)
11172
self.progress("Setting %s to %f" % (parameter_name, new_parameter_value))
11173
self.set_parameter(parameter_name, new_parameter_value)
11174
except Exception as e:
11175
ex = e
11176
11177
self.progress("Resetting SIM_BARO_COUNT")
11178
self.set_parameter("SIM_BARO_COUNT", old_sim_baro_count)
11179
11180
if self.is_tracker():
11181
# starts armed...
11182
self.progress("Disarming tracker")
11183
self.disarm_vehicle(force=True)
11184
11185
self.progress("Calling reboot-sitl ")
11186
self.reboot_sitl(required_bootcount=2)
11187
11188
if ex is not None:
11189
raise ex
11190
11191
if self.get_parameter(parameter_name) != new_parameter_value:
11192
raise NotAchievedException("Parameter value did not stick")
11193
11194
def InitialMode(self):
11195
'''Test initial mode switching'''
11196
if self.is_copter():
11197
init_mode = (9, "LAND")
11198
if self.is_rover():
11199
init_mode = (4, "HOLD")
11200
if self.is_plane():
11201
init_mode = (13, "TAKEOFF")
11202
if self.is_tracker():
11203
init_mode = (1, "STOP")
11204
if self.is_sub():
11205
return # NOT Supported yet
11206
self.context_push()
11207
self.set_parameter("SIM_RC_FAIL", 1)
11208
self.progress("Setting INITIAL_MODE to %s" % init_mode[1])
11209
self.set_parameter("INITIAL_MODE", init_mode[0])
11210
self.reboot_sitl()
11211
self.wait_mode(init_mode[1])
11212
self.progress("Testing back mode switch")
11213
self.set_parameter("SIM_RC_FAIL", 0)
11214
self.wait_for_mode_switch_poll()
11215
self.context_pop()
11216
self.reboot_sitl()
11217
11218
def Gripper(self):
11219
'''Test gripper'''
11220
self.GripperType(1) # servo
11221
self.GripperType(2) # EPM
11222
11223
def GripperType(self, gripper_type):
11224
'''test specific gripper type'''
11225
self.context_push()
11226
self.set_parameters({
11227
"GRIP_ENABLE": 1,
11228
"GRIP_GRAB": 2000,
11229
"GRIP_RELEASE": 1000,
11230
"GRIP_TYPE": gripper_type,
11231
"SIM_GRPS_ENABLE": 1,
11232
"SIM_GRPS_PIN": 8,
11233
"SERVO8_FUNCTION": 28,
11234
"SERVO8_MIN": 1000,
11235
"SERVO8_MAX": 2000,
11236
"SERVO9_MIN": 1000,
11237
"SERVO9_MAX": 2000,
11238
"RC9_OPTION": 19,
11239
})
11240
self.set_rc(9, 1500)
11241
self.reboot_sitl()
11242
self.progress("Waiting for ready to arm")
11243
self.wait_ready_to_arm()
11244
self.progress("Test gripper with RC9_OPTION")
11245
self.progress("Releasing load")
11246
# non strict string matching because of catching text issue....
11247
self.context_collect('STATUSTEXT')
11248
self.set_rc(9, 1000)
11249
self.wait_text("Gripper load releas", check_context=True)
11250
self.progress("Grabbing load")
11251
self.set_rc(9, 2000)
11252
self.wait_text("Gripper load grabb", check_context=True)
11253
self.context_clear_collection('STATUSTEXT')
11254
self.progress("Releasing load")
11255
self.set_rc(9, 1000)
11256
self.wait_text("Gripper load releas", check_context=True)
11257
self.progress("Grabbing load")
11258
self.set_rc(9, 2000)
11259
self.wait_text("Gripper load grabb", check_context=True)
11260
self.progress("Test gripper with Mavlink cmd")
11261
11262
self.context_collect('STATUSTEXT')
11263
self.progress("Releasing load")
11264
self.run_cmd(
11265
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11266
p1=1,
11267
p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE
11268
)
11269
self.wait_text("Gripper load releas", check_context=True)
11270
self.progress("Grabbing load")
11271
self.run_cmd(
11272
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11273
p1=1,
11274
p2=mavutil.mavlink.GRIPPER_ACTION_GRAB
11275
)
11276
self.wait_text("Gripper load grabb", check_context=True)
11277
11278
self.context_clear_collection('STATUSTEXT')
11279
self.progress("Releasing load")
11280
self.run_cmd_int(
11281
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11282
p1=1,
11283
p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE
11284
)
11285
self.wait_text("Gripper load releas", check_context=True)
11286
11287
self.progress("Grabbing load")
11288
self.run_cmd_int(
11289
mavutil.mavlink.MAV_CMD_DO_GRIPPER,
11290
p1=1,
11291
p2=mavutil.mavlink.GRIPPER_ACTION_GRAB
11292
)
11293
self.wait_text("Gripper load grabb", check_context=True)
11294
11295
self.context_pop()
11296
self.reboot_sitl()
11297
11298
def TestLocalHomePosition(self):
11299
"""Test local home position is sent in HOME_POSITION message"""
11300
self.context_push()
11301
self.wait_ready_to_arm()
11302
11303
# set home to a new location
11304
self.mav.mav.command_long_send(1,
11305
1,
11306
mavutil.mavlink.MAV_CMD_DO_SET_HOME,
11307
0,
11308
0,
11309
0,
11310
0,
11311
0,
11312
-35.357466,
11313
149.142589,
11314
630)
11315
11316
# check home after home set
11317
m = self.assert_receive_message("HOME_POSITION", timeout=5)
11318
if abs(m.x) < 10 or abs(m.y) < 10 or abs(m.z) < 10:
11319
raise NotAchievedException("Failed to get local home position: (got=%u, %u, %u)", m.x, m.y, m.z)
11320
else:
11321
self.progress("Received local home position successfully: (got=%f, %f, %f)" %
11322
(m.x, m.y, m.z))
11323
11324
self.context_pop()
11325
self.reboot_sitl()
11326
11327
def install_terrain_handlers_context(self):
11328
'''install a message handler into the current context which will
11329
listen for an fulfill terrain requests from ArduPilot. Will
11330
die if the data is not available - but
11331
self.terrain_in_offline_mode can be set to true in the
11332
constructor to change this behaviour
11333
'''
11334
11335
def check_terrain_requests(mav, m):
11336
if m.get_type() != 'TERRAIN_REQUEST':
11337
return
11338
self.progress("Processing TERRAIN_REQUEST (%s)" %
11339
self.dump_message_verbose(m))
11340
# swiped from mav_terrain.py
11341
for bit in range(56):
11342
if m.mask & (1 << bit) == 0:
11343
continue
11344
11345
lat = m.lat * 1.0e-7
11346
lon = m.lon * 1.0e-7
11347
bit_spacing = m.grid_spacing * 4
11348
(lat, lon) = mp_util.gps_offset(lat, lon,
11349
east=bit_spacing * (bit % 8),
11350
north=bit_spacing * (bit // 8))
11351
data = []
11352
for i in range(4*4):
11353
y = i % 4
11354
x = i // 4
11355
(lat2, lon2) = mp_util.gps_offset(lat, lon,
11356
east=m.grid_spacing * y,
11357
north=m.grid_spacing * x)
11358
# if we are in online mode then we'll try to fetch
11359
# from the internet into the cache dir:
11360
for i in range(120):
11361
alt = self.elevationmodel.GetElevation(lat2, lon2)
11362
if alt is not None:
11363
break
11364
if self.terrain_in_offline_mode:
11365
break
11366
self.progress("No elevation data for (%f %f); retry" %
11367
(lat2, lon2))
11368
time.sleep(1)
11369
if alt is None:
11370
# no data - we can't send the packet
11371
raise ValueError("No elevation data for (%f %f)" % (lat2, lon2))
11372
data.append(int(alt))
11373
self.terrain_data_messages_sent += 1
11374
self.mav.mav.terrain_data_send(m.lat,
11375
m.lon,
11376
m.grid_spacing,
11377
bit,
11378
data)
11379
11380
self.install_message_hook_context(check_terrain_requests)
11381
11382
def install_messageprinter_handlers_context(self, messages):
11383
'''monitor incoming messages, print them out'''
11384
def check_messages(mav, m):
11385
if m.get_type() not in messages:
11386
return
11387
self.progress(self.dump_message_verbose(m))
11388
11389
self.install_message_hook_context(check_messages)
11390
11391
def SetpointGlobalPos(self, timeout=100):
11392
"""Test set position message in guided mode."""
11393
# Disable heading and yaw test on rover type
11394
11395
if self.is_rover():
11396
test_alt = True
11397
test_heading = False
11398
test_yaw_rate = False
11399
else:
11400
test_alt = True
11401
test_heading = True
11402
test_yaw_rate = True
11403
11404
self.install_terrain_handlers_context()
11405
11406
self.set_parameter("FS_GCS_ENABLE", 0)
11407
self.change_mode("GUIDED")
11408
self.wait_ready_to_arm()
11409
self.arm_vehicle()
11410
11411
if self.is_copter() or self.is_heli():
11412
self.user_takeoff(alt_min=50)
11413
11414
targetpos = self.mav.location()
11415
wp_accuracy = None
11416
if self.is_copter() or self.is_heli():
11417
wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)
11418
wp_accuracy = wp_accuracy * 0.01 # cm to m
11419
if self.is_plane() or self.is_rover():
11420
wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)
11421
if wp_accuracy is None:
11422
raise ValueError()
11423
11424
def to_alt_frame(alt, mav_frame):
11425
if mav_frame in ["MAV_FRAME_GLOBAL_RELATIVE_ALT",
11426
"MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",
11427
"MAV_FRAME_GLOBAL_TERRAIN_ALT",
11428
"MAV_FRAME_GLOBAL_TERRAIN_ALT_INT"]:
11429
home = self.home_position_as_mav_location()
11430
return alt - home.alt
11431
else:
11432
return alt
11433
11434
def send_target_position(lat, lng, alt, mav_frame):
11435
self.mav.mav.set_position_target_global_int_send(
11436
0, # timestamp
11437
self.sysid_thismav(), # target system_id
11438
1, # target component id
11439
mav_frame,
11440
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11441
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11442
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11443
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11444
int(lat * 1.0e7), # lat
11445
int(lng * 1.0e7), # lon
11446
alt, # alt
11447
0, # vx
11448
0, # vy
11449
0, # vz
11450
0, # afx
11451
0, # afy
11452
0, # afz
11453
0, # yaw
11454
0, # yawrate
11455
)
11456
11457
def testpos(self, targetpos : mavutil.location, test_alt : bool, frame_name : str, frame):
11458
send_target_position(targetpos.lat, targetpos.lng, to_alt_frame(targetpos.alt, frame_name), frame)
11459
self.wait_location(
11460
targetpos,
11461
accuracy=wp_accuracy,
11462
timeout=timeout,
11463
height_accuracy=(2 if test_alt else None),
11464
minimum_duration=2,
11465
)
11466
11467
for frame in MAV_FRAMES_TO_TEST:
11468
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
11469
self.start_subtest("Testing Set Position in %s" % frame_name)
11470
self.start_subtest("Changing Latitude")
11471
targetpos.lat += 0.0001
11472
if test_alt:
11473
targetpos.alt += 5
11474
testpos(self, targetpos, test_alt, frame_name, frame)
11475
11476
self.start_subtest("Changing Longitude")
11477
targetpos.lng += 0.0001
11478
if test_alt:
11479
targetpos.alt -= 5
11480
testpos(self, targetpos, test_alt, frame_name, frame)
11481
11482
self.start_subtest("Revert Latitude")
11483
targetpos.lat -= 0.0001
11484
if test_alt:
11485
targetpos.alt += 5
11486
testpos(self, targetpos, test_alt, frame_name, frame)
11487
11488
self.start_subtest("Revert Longitude")
11489
targetpos.lng -= 0.0001
11490
if test_alt:
11491
targetpos.alt -= 5
11492
testpos(self, targetpos, test_alt, frame_name, frame)
11493
11494
if test_heading:
11495
self.start_subtest("Testing Yaw targetting in %s" % frame_name)
11496
self.progress("Changing Latitude and Heading")
11497
targetpos.lat += 0.0001
11498
if test_alt:
11499
targetpos.alt += 5
11500
self.mav.mav.set_position_target_global_int_send(
11501
0, # timestamp
11502
self.sysid_thismav(), # target system_id
11503
1, # target component id
11504
frame,
11505
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11506
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11507
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11508
int(targetpos.lat * 1.0e7), # lat
11509
int(targetpos.lng * 1.0e7), # lon
11510
to_alt_frame(targetpos.alt, frame_name), # alt
11511
0, # vx
11512
0, # vy
11513
0, # vz
11514
0, # afx
11515
0, # afy
11516
0, # afz
11517
math.radians(42), # yaw
11518
0, # yawrate
11519
)
11520
self.wait_location(
11521
targetpos,
11522
accuracy=wp_accuracy,
11523
timeout=timeout,
11524
height_accuracy=(2 if test_alt else None),
11525
minimum_duration=2,
11526
)
11527
self.wait_heading(42, minimum_duration=5, timeout=timeout)
11528
11529
self.start_subtest("Revert Latitude and Heading")
11530
targetpos.lat -= 0.0001
11531
if test_alt:
11532
targetpos.alt -= 5
11533
self.mav.mav.set_position_target_global_int_send(
11534
0, # timestamp
11535
self.sysid_thismav(), # target system_id
11536
1, # target component id
11537
frame,
11538
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11539
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11540
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11541
int(targetpos.lat * 1.0e7), # lat
11542
int(targetpos.lng * 1.0e7), # lon
11543
to_alt_frame(targetpos.alt, frame_name), # alt
11544
0, # vx
11545
0, # vy
11546
0, # vz
11547
0, # afx
11548
0, # afy
11549
0, # afz
11550
math.radians(0), # yaw
11551
0, # yawrate
11552
)
11553
self.wait_location(
11554
targetpos,
11555
accuracy=wp_accuracy,
11556
timeout=timeout,
11557
height_accuracy=(2 if test_alt else None),
11558
minimum_duration=2,
11559
)
11560
self.wait_heading(0, minimum_duration=5, timeout=timeout)
11561
11562
if test_yaw_rate:
11563
self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)
11564
11565
def send_yaw_rate(rate, target=None):
11566
self.mav.mav.set_position_target_global_int_send(
11567
0, # timestamp
11568
self.sysid_thismav(), # target system_id
11569
1, # target component id
11570
frame,
11571
MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE |
11572
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11573
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
11574
int(targetpos.lat * 1.0e7), # lat
11575
int(targetpos.lng * 1.0e7), # lon
11576
to_alt_frame(targetpos.alt, frame_name), # alt
11577
0, # vx
11578
0, # vy
11579
0, # vz
11580
0, # afx
11581
0, # afy
11582
0, # afz
11583
0, # yaw
11584
rate, # yawrate in rad/s
11585
)
11586
11587
self.start_subtest("Changing Latitude and Yaw rate")
11588
target_rate = 1.0 # in rad/s
11589
targetpos.lat += 0.0001
11590
if test_alt:
11591
targetpos.alt += 5
11592
self.wait_yaw_speed(target_rate, timeout=timeout,
11593
called_function=lambda plop, empty: send_yaw_rate(
11594
target_rate, None), minimum_duration=5)
11595
self.wait_location(
11596
targetpos,
11597
accuracy=wp_accuracy,
11598
timeout=timeout,
11599
height_accuracy=(2 if test_alt else None),
11600
)
11601
11602
self.start_subtest("Revert Latitude and invert Yaw rate")
11603
target_rate = -1.0
11604
targetpos.lat -= 0.0001
11605
if test_alt:
11606
targetpos.alt -= 5
11607
self.wait_yaw_speed(target_rate, timeout=timeout,
11608
called_function=lambda plop, empty: send_yaw_rate(
11609
target_rate, None), minimum_duration=5)
11610
self.wait_location(
11611
targetpos,
11612
accuracy=wp_accuracy,
11613
timeout=timeout,
11614
height_accuracy=(2 if test_alt else None),
11615
)
11616
self.start_subtest("Changing Yaw rate to zero")
11617
target_rate = 0.0
11618
self.wait_yaw_speed(target_rate, timeout=timeout,
11619
called_function=lambda plop, empty: send_yaw_rate(
11620
target_rate, None), minimum_duration=5)
11621
11622
self.progress("Getting back to home and disarm")
11623
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
11624
self.disarm_vehicle()
11625
11626
def SetpointBadVel(self, timeout=30):
11627
'''try feeding in a very, very bad velocity and make sure it is ignored'''
11628
self.takeoff(mode='GUIDED')
11629
# following values from a real log:
11630
target_speed = Vector3(-3.6019095525029597e+30,
11631
1.7796490496925177e-41,
11632
3.0557017120313744e-26)
11633
11634
self.progress("Feeding in bad global data, hoping we don't move")
11635
11636
def send_speed_vector_global_int(vector , mav_frame):
11637
self.mav.mav.set_position_target_global_int_send(
11638
0, # timestamp
11639
self.sysid_thismav(), # target system_id
11640
1, # target component id
11641
mav_frame,
11642
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11643
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11644
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11645
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11646
0,
11647
0,
11648
0,
11649
vector.x, # vx
11650
vector.y, # vy
11651
vector.z, # vz
11652
0, # afx
11653
0, # afy
11654
0, # afz
11655
0, # yaw
11656
0, # yawrate
11657
)
11658
self.wait_speed_vector(
11659
Vector3(0, 0, 0),
11660
timeout=timeout,
11661
called_function=lambda plop, empty: send_speed_vector_global_int(target_speed, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT), # noqa
11662
minimum_duration=10
11663
)
11664
11665
self.progress("Feeding in bad local data, hoping we don't move")
11666
11667
def send_speed_vector_local_ned(vector , mav_frame):
11668
self.mav.mav.set_position_target_local_ned_send(
11669
0, # timestamp
11670
self.sysid_thismav(), # target system_id
11671
1, # target component id
11672
mav_frame,
11673
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11674
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11675
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11676
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11677
0,
11678
0,
11679
0,
11680
vector.x, # vx
11681
vector.y, # vy
11682
vector.z, # vz
11683
0, # afx
11684
0, # afy
11685
0, # afz
11686
0, # yaw
11687
0, # yawrate
11688
)
11689
self.wait_speed_vector(
11690
Vector3(0, 0, 0),
11691
timeout=timeout,
11692
called_function=lambda plop, empty: send_speed_vector_local_ned(target_speed, mavutil.mavlink.MAV_FRAME_LOCAL_NED), # noqa
11693
minimum_duration=10
11694
)
11695
11696
self.do_RTL()
11697
11698
def SetpointGlobalVel(self, timeout=30):
11699
"""Test set position message in guided mode."""
11700
# Disable heading and yaw rate test on rover type
11701
if self.is_rover():
11702
test_vz = False
11703
test_heading = False
11704
test_yaw_rate = False
11705
else:
11706
test_vz = True
11707
test_heading = True
11708
test_yaw_rate = True
11709
11710
self.install_terrain_handlers_context()
11711
11712
self.set_parameter("FS_GCS_ENABLE", 0)
11713
self.change_mode("GUIDED")
11714
self.wait_ready_to_arm()
11715
self.arm_vehicle()
11716
11717
if self.is_copter() or self.is_heli():
11718
self.user_takeoff(alt_min=50)
11719
11720
target_speed = Vector3(1.0, 0.0, 0.0)
11721
11722
wp_accuracy = None
11723
if self.is_copter() or self.is_heli():
11724
wp_accuracy = self.get_parameter("WPNAV_RADIUS", attempts=2)
11725
wp_accuracy = wp_accuracy * 0.01 # cm to m
11726
if self.is_plane() or self.is_rover():
11727
wp_accuracy = self.get_parameter("WP_RADIUS", attempts=2)
11728
if wp_accuracy is None:
11729
raise ValueError()
11730
11731
def send_speed_vector(vector, mav_frame):
11732
self.mav.mav.set_position_target_global_int_send(
11733
0, # timestamp
11734
self.sysid_thismav(), # target system_id
11735
1, # target component id
11736
mav_frame,
11737
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11738
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11739
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE |
11740
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11741
0,
11742
0,
11743
0,
11744
vector.x, # vx
11745
vector.y, # vy
11746
vector.z, # vz
11747
0, # afx
11748
0, # afy
11749
0, # afz
11750
0, # yaw
11751
0, # yawrate
11752
)
11753
11754
for frame in MAV_FRAMES_TO_TEST:
11755
frame_name = mavutil.mavlink.enums["MAV_FRAME"][frame].name
11756
self.start_subtest("Testing Set Velocity in %s" % frame_name)
11757
self.progress("Changing Vx speed")
11758
self.wait_speed_vector(
11759
target_speed,
11760
timeout=timeout,
11761
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11762
minimum_duration=2
11763
)
11764
11765
self.start_subtest("Add Vy speed")
11766
target_speed.y = 1.0
11767
self.wait_speed_vector(
11768
target_speed,
11769
timeout=timeout,
11770
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11771
minimum_duration=2)
11772
11773
self.start_subtest("Add Vz speed")
11774
if test_vz:
11775
target_speed.z = 1.0
11776
else:
11777
target_speed.z = 0.0
11778
self.wait_speed_vector(
11779
target_speed,
11780
timeout=timeout,
11781
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11782
minimum_duration=2
11783
)
11784
11785
self.start_subtest("Invert Vz speed")
11786
if test_vz:
11787
target_speed.z = -1.0
11788
else:
11789
target_speed.z = 0.0
11790
self.wait_speed_vector(
11791
target_speed,
11792
timeout=timeout,
11793
called_function=lambda plop, empty: send_speed_vector(target_speed, frame), minimum_duration=2
11794
)
11795
11796
self.start_subtest("Invert Vx speed")
11797
target_speed.x = -1.0
11798
self.wait_speed_vector(
11799
target_speed,
11800
timeout=timeout,
11801
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11802
minimum_duration=2
11803
)
11804
11805
self.start_subtest("Invert Vy speed")
11806
target_speed.y = -1.0
11807
self.wait_speed_vector(
11808
target_speed,
11809
timeout=timeout,
11810
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11811
minimum_duration=2
11812
)
11813
11814
self.start_subtest("Set Speed to zero")
11815
target_speed.x = 0.0
11816
target_speed.y = 0.0
11817
target_speed.z = 0.0
11818
self.wait_speed_vector(
11819
target_speed,
11820
timeout=timeout,
11821
called_function=lambda plop, empty: send_speed_vector(target_speed, frame),
11822
minimum_duration=2
11823
)
11824
11825
if test_heading:
11826
self.start_subtest("Testing Yaw targetting in %s" % frame_name)
11827
11828
def send_yaw_target(yaw, mav_frame):
11829
self.mav.mav.set_position_target_global_int_send(
11830
0, # timestamp
11831
self.sysid_thismav(), # target system_id
11832
1, # target component id
11833
mav_frame,
11834
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11835
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11836
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11837
0,
11838
0,
11839
0,
11840
0, # vx
11841
0, # vy
11842
0, # vz
11843
0, # afx
11844
0, # afy
11845
0, # afz
11846
math.radians(yaw), # yaw
11847
0, # yawrate
11848
)
11849
11850
target_speed.x = 1.0
11851
target_speed.y = 1.0
11852
if test_vz:
11853
target_speed.z = -1.0
11854
else:
11855
target_speed.z = 0.0
11856
11857
def send_yaw_target_vel(yaw, vector, mav_frame):
11858
self.mav.mav.set_position_target_global_int_send(
11859
0, # timestamp
11860
self.sysid_thismav(), # target system_id
11861
1, # target component id
11862
mav_frame,
11863
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11864
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11865
MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE,
11866
0,
11867
0,
11868
0,
11869
vector.x, # vx
11870
vector.y, # vy
11871
vector.z, # vz
11872
0, # afx
11873
0, # afy
11874
0, # afz
11875
math.radians(yaw), # yaw
11876
0, # yawrate
11877
)
11878
11879
self.start_subtest("Target a fixed Heading")
11880
target_yaw = 42.0
11881
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
11882
called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))
11883
11884
self.start_subtest("Set target Heading")
11885
target_yaw = 0.0
11886
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
11887
called_function=lambda plop, empty: send_yaw_target(target_yaw, frame))
11888
11889
self.start_subtest("Add Vx, Vy, Vz speed and target a fixed Heading")
11890
target_yaw = 42.0
11891
self.wait_heading(
11892
target_yaw,
11893
minimum_duration=5,
11894
timeout=timeout,
11895
called_function=lambda p, e: send_yaw_target_vel(target_yaw,
11896
target_speed,
11897
frame)
11898
)
11899
self.wait_speed_vector(
11900
target_speed,
11901
called_function=lambda p, e: send_yaw_target_vel(target_yaw,
11902
target_speed,
11903
frame)
11904
)
11905
11906
self.start_subtest("Stop Vx, Vy, Vz speed and target zero Heading")
11907
target_yaw = 0.0
11908
target_speed.x = 0.0
11909
target_speed.y = 0.0
11910
target_speed.z = 0.0
11911
self.wait_heading(target_yaw, minimum_duration=5, timeout=timeout,
11912
called_function=lambda plop, empty: send_yaw_target_vel(target_yaw, target_speed, frame))
11913
self.wait_speed_vector(
11914
target_speed,
11915
timeout=timeout,
11916
called_function=lambda p, ee: send_yaw_target_vel(target_yaw,
11917
target_speed,
11918
frame),
11919
minimum_duration=2
11920
)
11921
11922
if test_yaw_rate:
11923
self.start_subtest("Testing Yaw Rate targetting in %s" % frame_name)
11924
11925
def send_yaw_rate(rate, mav_frame):
11926
self.mav.mav.set_position_target_global_int_send(
11927
0, # timestamp
11928
self.sysid_thismav(), # target system_id
11929
1, # target component id
11930
mav_frame,
11931
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11932
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11933
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
11934
0,
11935
0,
11936
0,
11937
0, # vx
11938
0, # vy
11939
0, # vz
11940
0, # afx
11941
0, # afy
11942
0, # afz
11943
0, # yaw
11944
rate, # yawrate in rad/s
11945
)
11946
11947
target_speed.x = 1.0
11948
target_speed.y = 1.0
11949
if test_vz:
11950
target_speed.z = -1.0
11951
else:
11952
target_speed.z = 0.0
11953
11954
def send_yaw_rate_vel(rate, vector, mav_frame):
11955
self.mav.mav.set_position_target_global_int_send(
11956
0, # timestamp
11957
self.sysid_thismav(), # target system_id
11958
1, # target component id
11959
mav_frame,
11960
MAV_POS_TARGET_TYPE_MASK.POS_IGNORE |
11961
MAV_POS_TARGET_TYPE_MASK.ACC_IGNORE |
11962
MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE,
11963
0,
11964
0,
11965
0,
11966
vector.x, # vx
11967
vector.y, # vy
11968
vector.z, # vz
11969
0, # afx
11970
0, # afy
11971
0, # afz
11972
0, # yaw
11973
rate, # yawrate in rad/s
11974
)
11975
11976
self.start_subtest("Set Yaw rate")
11977
target_rate = 1.0
11978
self.wait_yaw_speed(target_rate, timeout=timeout,
11979
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
11980
11981
self.start_subtest("Invert Yaw rate")
11982
target_rate = -1.0
11983
self.wait_yaw_speed(target_rate, timeout=timeout,
11984
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
11985
11986
self.start_subtest("Stop Yaw rate")
11987
target_rate = 0.0
11988
self.wait_yaw_speed(target_rate, timeout=timeout,
11989
called_function=lambda plop, empty: send_yaw_rate(target_rate, frame), minimum_duration=2)
11990
11991
self.start_subtest("Set Yaw Rate and Vx, Vy, Vz speed")
11992
target_rate = 1.0
11993
self.wait_yaw_speed(
11994
target_rate,
11995
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
11996
target_speed,
11997
frame),
11998
minimum_duration=2
11999
)
12000
self.wait_speed_vector(
12001
target_speed,
12002
timeout=timeout,
12003
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12004
target_speed,
12005
frame),
12006
minimum_duration=2
12007
)
12008
12009
target_rate = -1.0
12010
target_speed.x = -1.0
12011
target_speed.y = -1.0
12012
if test_vz:
12013
target_speed.z = 1.0
12014
else:
12015
target_speed.z = 0.0
12016
self.start_subtest("Invert Vx, Vy, Vz speed")
12017
self.wait_yaw_speed(
12018
target_rate,
12019
timeout=timeout,
12020
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12021
target_speed,
12022
frame),
12023
minimum_duration=2
12024
)
12025
self.wait_speed_vector(
12026
target_speed,
12027
timeout=timeout,
12028
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12029
target_speed,
12030
frame),
12031
minimum_duration=2
12032
)
12033
12034
target_rate = 0.0
12035
target_speed.x = 0.0
12036
target_speed.y = 0.0
12037
target_speed.z = 0.0
12038
self.start_subtest("Stop Yaw rate and all speed")
12039
self.wait_yaw_speed(
12040
target_rate,
12041
timeout=timeout,
12042
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12043
target_speed,
12044
frame),
12045
minimum_duration=2
12046
)
12047
self.wait_speed_vector(
12048
target_speed,
12049
timeout=timeout,
12050
called_function=lambda p, e: send_yaw_rate_vel(target_rate,
12051
target_speed,
12052
frame),
12053
minimum_duration=2
12054
)
12055
12056
self.progress("Getting back to home and disarm")
12057
self.do_RTL(distance_min=0, distance_max=wp_accuracy)
12058
self.disarm_vehicle()
12059
12060
def is_blimp(self):
12061
return False
12062
12063
def is_copter(self):
12064
return False
12065
12066
def is_sub(self):
12067
return False
12068
12069
def is_plane(self):
12070
return False
12071
12072
def is_rover(self):
12073
return False
12074
12075
def is_balancebot(self):
12076
return False
12077
12078
def is_heli(self):
12079
return False
12080
12081
def is_tracker(self):
12082
return False
12083
12084
def initial_mode(self):
12085
'''return mode vehicle should start in with no RC inputs set'''
12086
return None
12087
12088
def initial_mode_switch_mode(self):
12089
'''return mode vehicle should start in with default RC inputs set'''
12090
return None
12091
12092
def upload_fences_from_locations(self, fences, target_system=1, target_component=1):
12093
seq = 0
12094
items = []
12095
12096
for (vertex_type, locs) in fences:
12097
if isinstance(locs, dict):
12098
# circular fence
12099
item = self.mav.mav.mission_item_int_encode(
12100
target_system,
12101
target_component,
12102
seq, # seq
12103
mavutil.mavlink.MAV_FRAME_GLOBAL,
12104
vertex_type,
12105
0, # current
12106
0, # autocontinue
12107
locs["radius"], # p1
12108
0, # p2
12109
0, # p3
12110
0, # p4
12111
int(locs["loc"].lat * 1e7), # latitude
12112
int(locs["loc"].lng * 1e7), # longitude
12113
33.0000, # altitude
12114
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
12115
seq += 1
12116
items.append(item)
12117
continue
12118
count = len(locs)
12119
for loc in locs:
12120
item = self.mav.mav.mission_item_int_encode(
12121
target_system,
12122
target_component,
12123
seq, # seq
12124
mavutil.mavlink.MAV_FRAME_GLOBAL,
12125
vertex_type,
12126
0, # current
12127
0, # autocontinue
12128
count, # p1
12129
0, # p2
12130
0, # p3
12131
0, # p4
12132
int(loc.lat * 1e7), # latitude
12133
int(loc.lng * 1e7), # longitude
12134
33.0000, # altitude
12135
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
12136
seq += 1
12137
items.append(item)
12138
12139
self.check_fence_upload_download(items)
12140
12141
def rally_MISSION_ITEM_INT_from_loc(self, loc):
12142
return self.create_MISSION_ITEM_INT(
12143
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
12144
x=int(loc.lat*1e7),
12145
y=int(loc.lng*1e7),
12146
z=loc.alt,
12147
frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
12148
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY
12149
)
12150
12151
def upload_rally_points_from_locations(self, rally_point_locs):
12152
'''takes a sequence of locations, sets vehicle rally points to those locations'''
12153
items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs]
12154
self.correct_wp_seq_numbers(items)
12155
self.check_rally_upload_download(items)
12156
12157
def wait_for_initial_mode(self):
12158
'''wait until we get a heartbeat with an expected initial mode (the
12159
one specified in the vehicle constructor)'''
12160
want = self.initial_mode()
12161
if want is None:
12162
return
12163
self.progress("Waiting for initial mode %s" % want)
12164
self.wait_mode(want)
12165
12166
def wait_for_mode_switch_poll(self):
12167
'''look for a transition from boot-up-mode (e.g. the flightmode
12168
specificied in Copter's constructor) to the one specified by the mode
12169
switch value'''
12170
want = self.initial_mode_switch_mode()
12171
if want is None:
12172
return
12173
self.progress("Waiting for mode-switch mode %s" % want)
12174
self.wait_mode(want)
12175
12176
def start_subtest(self, description):
12177
self.progress("-")
12178
self.progress("---------- %s ----------" % description)
12179
self.progress("-")
12180
12181
def start_subsubtest(self, description):
12182
self.progress(".")
12183
self.progress(".......... %s .........." % description)
12184
self.progress(".")
12185
12186
def end_subtest(self, description):
12187
'''TODO: sanity checks?'''
12188
pass
12189
12190
def end_subsubtest(self, description):
12191
'''TODO: sanity checks?'''
12192
pass
12193
12194
def last_onboard_log(self):
12195
'''return number of last onboard log'''
12196
mavproxy = self.start_mavproxy()
12197
mavproxy.send("module load log\n")
12198
loaded_module = False
12199
mavproxy.expect(["Loaded module log", "module log already loaded"])
12200
if mavproxy.match.group(0) == "Loaded module log":
12201
loaded_module = True
12202
mavproxy.send("log list\n")
12203
mavproxy.expect(["lastLog ([0-9]+)", "No logs"])
12204
if mavproxy.match.group(0) == "No logs":
12205
num_log = None
12206
else:
12207
num_log = int(mavproxy.match.group(1))
12208
if loaded_module:
12209
mavproxy.send("module unload log\n")
12210
mavproxy.expect("Unloaded module log")
12211
self.stop_mavproxy(mavproxy)
12212
return num_log
12213
12214
def current_onboard_log_number(self):
12215
logs = self.download_full_log_list(print_logs=False)
12216
return sorted(logs.keys())[-1]
12217
12218
def current_onboard_log_filepath(self):
12219
'''return filepath to currently open dataflash log. We assume that's
12220
the latest log...'''
12221
logs = self.log_list()
12222
latest = logs[-1]
12223
return latest
12224
12225
def dfreader_for_path(self, path):
12226
return DFReader.DFReader_binary(path,
12227
zero_time_base=True)
12228
12229
def dfreader_for_current_onboard_log(self):
12230
return self.dfreader_for_path(self.current_onboard_log_filepath())
12231
12232
def current_onboard_log_contains_message(self, messagetype):
12233
self.progress("Checking (%s) for (%s)" %
12234
(self.current_onboard_log_filepath(), messagetype))
12235
dfreader = self.dfreader_for_current_onboard_log()
12236
m = dfreader.recv_match(type=messagetype)
12237
print("m=%s" % str(m))
12238
return m is not None
12239
12240
def assert_current_onboard_log_contains_message(self, messagetype):
12241
if not self.current_onboard_log_contains_message(messagetype):
12242
raise NotAchievedException("Current onboard log does not contain message %s" % messagetype)
12243
12244
def run_tests(self, tests) -> List[Result]:
12245
"""Autotest vehicle in SITL."""
12246
if self.run_tests_called:
12247
raise ValueError("run_tests called twice")
12248
self.run_tests_called = True
12249
12250
result_list = []
12251
12252
try:
12253
self.init()
12254
12255
self.progress("Waiting for a heartbeat with mavlink protocol %s"
12256
% self.mav.WIRE_PROTOCOL_VERSION)
12257
self.wait_heartbeat()
12258
self.wait_for_initial_mode()
12259
self.progress("Setting up RC parameters")
12260
self.set_rc_default()
12261
self.wait_for_mode_switch_poll()
12262
if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling
12263
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
12264
12265
for test in tests:
12266
self.drain_mav_unparsed()
12267
result_list.append(self.run_one_test(test))
12268
12269
except pexpect.TIMEOUT:
12270
self.progress("Failed with timeout")
12271
result = Result(test)
12272
result.passed = False
12273
result.reason = "Failed with timeout"
12274
result_list.append(result)
12275
if self.logs_dir:
12276
if glob.glob("core*") or glob.glob("ap-*.core"):
12277
self.check_logs("FRAMEWORK")
12278
12279
if self.rc_thread is not None:
12280
self.progress("Joining RC thread")
12281
self.rc_thread_should_quit = True
12282
self.rc_thread.join()
12283
self.rc_thread = None
12284
12285
if self.mav is not None:
12286
self.mav.close()
12287
self.mav = None
12288
12289
self.stop_SITL()
12290
12291
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
12292
model=self.frame)
12293
files = glob.glob("*" + valgrind_log)
12294
valgrind_failed = False
12295
for valgrind_log in files:
12296
os.chmod(valgrind_log, 0o644)
12297
if os.path.getsize(valgrind_log) > 0:
12298
target = self.buildlogs_path("%s-%s" % (
12299
self.log_name(),
12300
os.path.basename(valgrind_log)))
12301
self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target))
12302
shutil.move(valgrind_log, target)
12303
valgrind_failed = True
12304
if valgrind_failed:
12305
result_list.append(ValgrindFailedResult())
12306
12307
return result_list
12308
12309
def dictdiff(self, dict1, dict2):
12310
fred = copy.copy(dict1)
12311
for key in dict2.keys():
12312
try:
12313
del fred[key]
12314
except KeyError:
12315
pass
12316
return fred
12317
12318
# download parameters tries to cope with its download being
12319
# interrupted or broken by simply retrying the download a few
12320
# times.
12321
def download_parameters(self, target_system, target_component):
12322
# try a simple fetch-all:
12323
last_parameter_received = 0
12324
attempt_count = 0
12325
start_done = False
12326
# make flake8 happy:
12327
count = 0
12328
expected_count = 0
12329
seen_ids = {}
12330
self.progress("Downloading parameters")
12331
debug = False
12332
while True:
12333
now = self.get_sim_time_cached()
12334
if not start_done or now - last_parameter_received > 10:
12335
start_done = True
12336
if attempt_count > 3:
12337
raise AutoTestTimeoutException("Failed to download parameters (have %s/%s) (seen_ids-count=%u)" %
12338
(str(count), str(expected_count), len(seen_ids.keys())))
12339
elif attempt_count != 0:
12340
self.progress("Download failed; retrying")
12341
self.delay_sim_time(1)
12342
debug = True
12343
self.drain_mav()
12344
self.mav.mav.param_request_list_send(target_system, target_component)
12345
attempt_count += 1
12346
count = 0
12347
expected_count = None
12348
seen_ids = {}
12349
id_seq = {}
12350
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=10)
12351
if m is None:
12352
raise AutoTestTimeoutException("tardy PARAM_VALUE (have %s/%s)" % (
12353
str(count), str(expected_count)))
12354
if m.param_index == 65535:
12355
self.progress("volunteered parameter: %s" % str(m))
12356
continue
12357
if debug:
12358
self.progress(" received id=%4u param_count=%4u %s=%f" %
12359
(m.param_index, m.param_count, m.param_id, m.param_value))
12360
if m.param_index >= m.param_count:
12361
raise ValueError("parameter index (%u) gte parameter count (%u)" %
12362
(m.param_index, m.param_count))
12363
if expected_count is None:
12364
expected_count = m.param_count
12365
else:
12366
if m.param_count != expected_count:
12367
raise ValueError("expected count changed")
12368
if m.param_id not in seen_ids:
12369
count += 1
12370
seen_ids[m.param_id] = m.param_value
12371
last_parameter_received = now
12372
if count == expected_count:
12373
break
12374
12375
self.progress("Downloaded %u parameters OK (attempt=%u)" %
12376
(count, attempt_count))
12377
return (seen_ids, id_seq)
12378
12379
def test_parameters_download(self):
12380
self.start_subtest("parameter download")
12381
target_system = self.sysid_thismav()
12382
target_component = 1
12383
self.progress("First Download:")
12384
(parameters, seq_id) = self.download_parameters(target_system, target_component)
12385
self.reboot_sitl()
12386
self.progress("Second download:")
12387
(parameters2, seq2_id) = self.download_parameters(target_system, target_component)
12388
12389
delta = self.dictdiff(parameters, parameters2)
12390
if len(delta) != 0:
12391
raise ValueError("Got %u fewer parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %
12392
(len(delta), len(parameters), len(parameters2), str(delta.keys())))
12393
12394
delta = self.dictdiff(parameters2, parameters)
12395
if len(delta) != 0:
12396
raise ValueError("Got %u extra parameters when downloading second time (before=%u vs after=%u) (delta=%s)" %
12397
(len(delta), len(parameters), len(parameters2), str(delta.keys())))
12398
12399
self.end_subsubtest("parameter download")
12400
12401
def test_enable_parameter(self):
12402
self.start_subtest("enable parameters")
12403
target_system = 1
12404
target_component = 1
12405
parameters = self.download_parameters(target_system, target_component)
12406
enable_parameter = self.sample_enable_parameter()
12407
if enable_parameter is None:
12408
self.progress("Skipping enable parameter check as no enable parameter supplied")
12409
return
12410
self.set_parameter(enable_parameter, 1)
12411
parameters2 = self.download_parameters(target_system, target_component)
12412
if len(parameters) == len(parameters2):
12413
raise NotAchievedException("Enable parameter did not increase no of parameters downloaded")
12414
self.end_subsubtest("enable download")
12415
12416
def test_parameters_mis_total(self):
12417
self.start_subsubtest("parameter mis_total")
12418
if self.is_tracker():
12419
# uses CMD_TOTAL not MIS_TOTAL, and it's in a scalr not a
12420
# group and it's generally all bad.
12421
return
12422
self.start_subtest("Ensure GCS is not able to set MIS_TOTAL")
12423
old_mt = self.get_parameter("MIS_TOTAL", attempts=20) # retries to avoid seeming race condition with MAVProxy
12424
ex = None
12425
try:
12426
self.set_parameter("MIS_TOTAL", 17, attempts=1)
12427
except ValueError as e:
12428
ex = e
12429
if ex is None:
12430
raise NotAchievedException("Set parameter when I shouldn't have")
12431
if old_mt != self.get_parameter("MIS_TOTAL"):
12432
raise NotAchievedException("Total has changed")
12433
12434
self.start_subtest("Ensure GCS is able to set other MIS_ parameters")
12435
self.set_parameter("MIS_OPTIONS", 1)
12436
if self.get_parameter("MIS_OPTIONS") != 1:
12437
raise NotAchievedException("Failed to set MIS_OPTIONS")
12438
12439
mavproxy = self.start_mavproxy()
12440
from_mavproxy = self.get_parameter_mavproxy(mavproxy, "MIS_OPTIONS")
12441
if from_mavproxy != 1:
12442
raise NotAchievedException("MAVProxy failed to get parameter")
12443
self.stop_mavproxy(mavproxy)
12444
12445
def test_parameter_documentation(self):
12446
'''ensure parameter documentation is valid'''
12447
self.start_subsubtest("Check all parameters are documented")
12448
self.test_parameter_documentation_get_all_parameters()
12449
12450
def Parameters(self):
12451
'''general small tests for parameter system'''
12452
if self.is_balancebot():
12453
# same binary and parameters as Rover
12454
return
12455
self.test_parameter_documentation()
12456
self.test_parameters_mis_total()
12457
self.test_parameters_download()
12458
12459
def disabled_tests(self):
12460
return {}
12461
12462
def test_parameter_checks_poscontrol(self, param_prefix):
12463
self.wait_ready_to_arm()
12464
self.context_push()
12465
self.set_parameter("%s_POSXY_P" % param_prefix, -1)
12466
self.run_cmd(
12467
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
12468
p1=1, # ARM
12469
timeout=4,
12470
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
12471
)
12472
self.context_pop()
12473
self.run_cmd(
12474
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
12475
p1=1, # ARM
12476
timeout=4,
12477
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
12478
)
12479
self.disarm_vehicle()
12480
12481
def assert_not_receiving_message(self, message, timeout=1, mav=None):
12482
self.progress("making sure we're not getting %s messages" % message)
12483
if mav is None:
12484
mav = self.mav
12485
m = mav.recv_match(type=message, blocking=True, timeout=timeout)
12486
if m is not None:
12487
raise PreconditionFailedException("Receiving %s messags" % message)
12488
12489
def PIDTuning(self):
12490
'''Test PID Tuning'''
12491
self.assert_not_receiving_message('PID_TUNING', timeout=5)
12492
self.set_parameter("GCS_PID_MASK", 1)
12493
self.progress("making sure we are now getting PID_TUNING messages")
12494
self.assert_receive_message('PID_TUNING', timeout=5)
12495
12496
def sample_mission_filename(self):
12497
return "flaps.txt"
12498
12499
def AdvancedFailsafe(self):
12500
'''Test Advanced Failsafe'''
12501
ex = None
12502
try:
12503
self.drain_mav()
12504
if self.is_plane(): # other vehicles can always terminate
12505
self.assert_no_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
12506
self.set_parameters({
12507
"AFS_ENABLE": 1,
12508
"SYSID_MYGCS": self.mav.source_system,
12509
})
12510
self.drain_mav()
12511
self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION)
12512
self.set_parameter("AFS_TERM_ACTION", 42)
12513
self.load_sample_mission()
12514
self.context_collect("STATUSTEXT")
12515
self.change_mode("AUTO") # must go to auto for AFS to latch on
12516
self.wait_statustext("AFS State: AFS_AUTO", check_context=True)
12517
if self.is_plane():
12518
self.change_mode("MANUAL")
12519
elif self.is_copter():
12520
self.change_mode("STABILIZE")
12521
12522
self.start_subtest("RC Failure")
12523
self.context_push()
12524
self.context_collect("STATUSTEXT")
12525
self.set_parameters({
12526
"AFS_RC_FAIL_TIME": 1,
12527
"SIM_RC_FAIL": 1,
12528
})
12529
self.wait_statustext("Terminating due to RC failure", check_context=True)
12530
self.context_pop()
12531
self.set_parameter("AFS_TERMINATE", 0)
12532
12533
if not self.is_plane():
12534
# plane requires a polygon fence...
12535
self.start_subtest("Altitude Limit breach")
12536
self.set_parameters({
12537
"AFS_AMSL_LIMIT": 100,
12538
"AFS_QNH_PRESSURE": 1015.2,
12539
})
12540
self.do_fence_enable()
12541
self.wait_statustext("Terminating due to fence breach", check_context=True)
12542
self.set_parameter("AFS_AMSL_LIMIT", 0)
12543
self.set_parameter("AFS_TERMINATE", 0)
12544
self.do_fence_disable()
12545
12546
self.start_subtest("GPS Failure")
12547
self.context_push()
12548
self.context_collect("STATUSTEXT")
12549
self.set_parameters({
12550
"AFS_MAX_GPS_LOSS": 1,
12551
"SIM_GPS1_ENABLE": 0,
12552
})
12553
self.wait_statustext("AFS State: GPS_LOSS", check_context=True)
12554
self.context_pop()
12555
self.set_parameter("AFS_TERMINATE", 0)
12556
12557
self.start_subtest("GCS Request")
12558
self.context_push()
12559
self.context_collect("STATUSTEXT")
12560
self.run_cmd(
12561
mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION,
12562
p1=1, # terminate
12563
)
12564
self.wait_statustext("Terminating due to GCS request", check_context=True)
12565
self.context_pop()
12566
self.set_parameter("AFS_TERMINATE", 0)
12567
12568
except Exception as e:
12569
ex = e
12570
try:
12571
self.do_fence_disable()
12572
except ValueError:
12573
# may not actually be enabled....
12574
pass
12575
if ex is not None:
12576
raise ex
12577
12578
def drain_mav_seconds(self, seconds):
12579
tstart = self.get_sim_time_cached()
12580
while self.get_sim_time_cached() - tstart < seconds:
12581
self.drain_mav()
12582
self.delay_sim_time(0.5)
12583
12584
def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT", verbose=False):
12585
tstart = self.get_sim_time()
12586
while True:
12587
now = self.get_sim_time_cached()
12588
if now - tstart > timeout:
12589
raise AutoTestTimeoutException("Did not get good GPS lock")
12590
m = self.mav.recv_match(type=message_type, blocking=True, timeout=0.1)
12591
if verbose:
12592
self.progress("Received: %s" % str(m))
12593
if m is None:
12594
continue
12595
if m.fix_type >= fix_type:
12596
break
12597
12598
def NMEAOutput(self):
12599
'''Test AHRS NMEA Output can be read by out NMEA GPS'''
12600
self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output
12601
self.set_parameter("GPS2_TYPE", 5) # GPS2 is NMEA
12602
port = self.spare_network_port()
12603
self.customise_SITL_commandline([
12604
"--serial4=tcp:%u" % port, # GPS2 is NMEA....
12605
"--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port
12606
])
12607
self.do_timesync_roundtrip()
12608
self.wait_gps_fix_type_gte(3)
12609
gps1 = self.mav.recv_match(type="GPS_RAW_INT", blocking=True, timeout=10)
12610
self.progress("gps1=(%s)" % str(gps1))
12611
if gps1 is None:
12612
raise NotAchievedException("Did not receive GPS_RAW_INT")
12613
tstart = self.get_sim_time()
12614
while True:
12615
now = self.get_sim_time_cached()
12616
if now - tstart > 20:
12617
raise NotAchievedException("NMEA output not updating?!")
12618
gps2 = self.mav.recv_match(type="GPS2_RAW", blocking=True, timeout=1)
12619
self.progress("gps2=%s" % str(gps2))
12620
if gps2 is None:
12621
continue
12622
if gps2.time_usec != 0:
12623
break
12624
max_distance = 1
12625
distance = self.get_distance_int(gps1, gps2)
12626
if distance > max_distance:
12627
raise NotAchievedException("NMEA output inaccurate (dist=%f want<%f)" %
12628
(distance, max_distance))
12629
12630
def mavproxy_load_module(self, mavproxy, module):
12631
mavproxy.send("module load %s\n" % module)
12632
mavproxy.expect("Loaded module %s" % module)
12633
12634
def mavproxy_unload_module(self, mavproxy, module):
12635
mavproxy.send("module unload %s\n" % module)
12636
mavproxy.expect("Unloaded module %s" % module)
12637
12638
def AccelCal(self):
12639
'''Accelerometer Calibration testing'''
12640
ex = None
12641
mavproxy = self.start_mavproxy()
12642
try:
12643
# setup with pre-existing accel offsets, to show that existing offsets don't
12644
# adversely affect a new cal
12645
pre_aofs = [Vector3(2.8, 1.2, 1.7),
12646
Vector3(0.2, -0.9, 2.9)]
12647
pre_ascale = [Vector3(0.95, 1.2, 0.98),
12648
Vector3(1.1, 1.0, 0.93)]
12649
aofs = [Vector3(0.7, -0.3, 1.8),
12650
Vector3(-2.1, 1.9, 2.3)]
12651
ascale = [Vector3(0.98, 1.12, 1.05),
12652
Vector3(1.11, 0.98, 0.96)]
12653
atrim = Vector3(0.05, -0.03, 0)
12654
pre_atrim = Vector3(-0.02, 0.04, 0)
12655
param_map = [("INS_ACCOFFS", "SIM_ACC1_BIAS", pre_aofs[0], aofs[0]),
12656
("INS_ACC2OFFS", "SIM_ACC2_BIAS", pre_aofs[1], aofs[1]),
12657
("INS_ACCSCAL", "SIM_ACC1_SCAL", pre_ascale[0], ascale[0]),
12658
("INS_ACC2SCAL", "SIM_ACC2_SCAL", pre_ascale[1], ascale[1]),
12659
("AHRS_TRIM", "SIM_ACC_TRIM", pre_atrim, atrim)]
12660
axes = ['X', 'Y', 'Z']
12661
12662
# form the pre-calibration params
12663
initial_params = {}
12664
for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:
12665
for axis in axes:
12666
initial_params[ins_prefix + "_" + axis] = getattr(pre_value, axis.lower())
12667
initial_params[sim_prefix + "_" + axis] = getattr(post_value, axis.lower())
12668
self.set_parameters(initial_params)
12669
self.customise_SITL_commandline(["-M", "calibration"])
12670
self.mavproxy_load_module(mavproxy, "sitl_calibration")
12671
self.mavproxy_load_module(mavproxy, "calibration")
12672
self.mavproxy_load_module(mavproxy, "relay")
12673
mavproxy.send("sitl_accelcal\n")
12674
mavproxy.send("accelcal\n")
12675
mavproxy.expect("Calibrated")
12676
for wanted in [
12677
"level",
12678
"on its LEFT side",
12679
"on its RIGHT side",
12680
"nose DOWN",
12681
"nose UP",
12682
"on its BACK",
12683
]:
12684
timeout = 2
12685
mavproxy.expect("Place vehicle %s and press any key." % wanted, timeout=timeout)
12686
mavproxy.expect("sitl_accelcal: sending attitude, please wait..", timeout=timeout)
12687
mavproxy.expect("sitl_accelcal: attitude detected, please press any key..", timeout=timeout)
12688
mavproxy.send("\n")
12689
mavproxy.expect(".*Calibration successful", timeout=timeout)
12690
self.drain_mav()
12691
12692
self.progress("Checking results")
12693
accuracy_pct = 0.5
12694
for (ins_prefix, sim_prefix, pre_value, post_value) in param_map:
12695
for axis in axes:
12696
pname = ins_prefix+"_"+axis
12697
v = self.get_parameter(pname)
12698
expected_v = getattr(post_value, axis.lower())
12699
if v == expected_v:
12700
continue
12701
error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)
12702
if error_pct > accuracy_pct:
12703
raise NotAchievedException(
12704
"Incorrect value %.6f for %s should be %.6f error %.2f%%" %
12705
(v, pname, expected_v, error_pct))
12706
else:
12707
self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct))
12708
except Exception as e:
12709
self.print_exception_caught(e)
12710
ex = e
12711
self.mavproxy_unload_module(mavproxy, "relay")
12712
self.mavproxy_unload_module(mavproxy, "calibration")
12713
self.mavproxy_unload_module(mavproxy, "sitl_calibration")
12714
self.stop_mavproxy(mavproxy)
12715
if ex is not None:
12716
raise ex
12717
12718
def ahrstrim_preflight_cal(self):
12719
# setup with non-zero accel offsets
12720
self.set_parameters({
12721
"INS_ACCOFFS_X": 0.7,
12722
"INS_ACCOFFS_Y": -0.3,
12723
"INS_ACCOFFS_Z": 1.8,
12724
"INS_ACC2OFFS_X": -2.1,
12725
"INS_ACC2OFFS_Y": 1.9,
12726
"INS_ACC2OFFS_Z": 2.3,
12727
"SIM_ACC1_BIAS_X": 0.7,
12728
"SIM_ACC1_BIAS_Y": -0.3,
12729
"SIM_ACC1_BIAS_Z": 1.8,
12730
"SIM_ACC2_BIAS_X": -2.1,
12731
"SIM_ACC2_BIAS_Y": 1.9,
12732
"SIM_ACC2_BIAS_Z": 2.3,
12733
"AHRS_TRIM_X": 0.05,
12734
"AHRS_TRIM_Y": -0.03,
12735
"SIM_ACC_TRIM_X": -0.04,
12736
"SIM_ACC_TRIM_Y": 0.05,
12737
})
12738
expected_parms = {
12739
"AHRS_TRIM_X": -0.04,
12740
"AHRS_TRIM_Y": 0.05,
12741
}
12742
12743
self.progress("Starting ahrstrim")
12744
self.drain_mav()
12745
self.mav.mav.command_long_send(self.sysid_thismav(), 1,
12746
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
12747
0, 0, 0, 0, 2, 0, 0)
12748
self.wait_statustext('Trim OK')
12749
self.drain_mav()
12750
12751
self.progress("Checking results")
12752
accuracy_pct = 0.2
12753
for (pname, expected_v) in expected_parms.items():
12754
v = self.get_parameter(pname)
12755
if v == expected_v:
12756
continue
12757
error_pct = 100.0 * abs(v - expected_v) / abs(expected_v)
12758
if error_pct > accuracy_pct:
12759
raise NotAchievedException(
12760
"Incorrect value %.6f for %s should be %.6f error %.2f%%" %
12761
(v, pname, expected_v, error_pct))
12762
self.progress("Correct value %.4f for %s error %.2f%%" %
12763
(v, pname, error_pct))
12764
12765
def user_takeoff(self, alt_min=30, timeout=30, max_err=5):
12766
'''takeoff using mavlink takeoff command'''
12767
self.run_cmd(
12768
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
12769
p7=alt_min, # param7
12770
)
12771
self.wait_altitude(alt_min - 1,
12772
(alt_min + max_err),
12773
relative=True,
12774
timeout=timeout)
12775
12776
def ahrstrim_attitude_correctness(self):
12777
self.wait_ready_to_arm()
12778
HOME = self.sitl_start_location()
12779
for heading in 0, 90:
12780
self.customise_SITL_commandline([
12781
"--home", "%s,%s,%s,%s" % (HOME.lat, HOME.lng, HOME.alt, heading)
12782
])
12783
for ahrs_type in [0, 2, 3]:
12784
self.start_subsubtest("Testing AHRS_TYPE=%u" % ahrs_type)
12785
self.context_push()
12786
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
12787
self.reboot_sitl()
12788
self.wait_prearm_sys_status_healthy()
12789
for (r, p) in [(0, 0), (9, 0), (2, -6), (10, 10)]:
12790
self.set_parameters({
12791
'AHRS_TRIM_X': math.radians(r),
12792
'AHRS_TRIM_Y': math.radians(p),
12793
"SIM_ACC_TRIM_X": math.radians(r),
12794
"SIM_ACC_TRIM_Y": math.radians(p),
12795
})
12796
self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5)
12797
if ahrs_type != 0: # we don't get secondary msgs while DCM is primary
12798
self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120)
12799
self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120)
12800
12801
self.context_pop()
12802
self.reboot_sitl()
12803
12804
def AHRSTrim(self):
12805
'''AHRS trim testing'''
12806
self.start_subtest("Attitude Correctness")
12807
self.ahrstrim_attitude_correctness()
12808
self.delay_sim_time(5)
12809
self.start_subtest("Preflight Calibration")
12810
self.ahrstrim_preflight_cal()
12811
12812
def Button(self):
12813
'''Test Buttons'''
12814
self.set_parameter("SIM_PIN_MASK", 0)
12815
self.set_parameter("BTN_ENABLE", 1)
12816
self.drain_mav()
12817
self.do_heartbeats(force=True)
12818
btn = 4
12819
pin = 3
12820
self.set_parameter("BTN_PIN%u" % btn, pin, verbose=True)
12821
m = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=1)
12822
self.progress("### m: %s" % str(m))
12823
if m is not None:
12824
# should not get a button-changed event here. The pins
12825
# are simulated pull-down
12826
raise NotAchievedException("Received BUTTON_CHANGE event")
12827
mask = 1 << pin
12828
self.set_parameter("SIM_PIN_MASK", mask)
12829
m = self.assert_receive_message('BUTTON_CHANGE', timeout=1, verbose=True)
12830
if not (m.state & mask):
12831
raise NotAchievedException("Bit not set in mask (got=%u want=%u)" % (m.state, mask))
12832
m2 = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=10)
12833
if m2 is None:
12834
raise NotAchievedException("Did not get repeat message")
12835
self.progress("### m2: %s" % str(m2))
12836
# wait for messages to stop coming:
12837
self.drain_mav_seconds(15)
12838
12839
new_mask = 0
12840
self.send_set_parameter("SIM_PIN_MASK", new_mask, verbose=True)
12841
m3 = self.mav.recv_match(type='BUTTON_CHANGE', blocking=True, timeout=1)
12842
if m3 is None:
12843
raise NotAchievedException("Did not get 'off' message")
12844
self.progress("### m3: %s" % str(m3))
12845
12846
if m.last_change_ms == m3.last_change_ms:
12847
raise NotAchievedException("last_change_ms same as first message")
12848
if m3.state != new_mask:
12849
raise NotAchievedException("Unexpected mask (want=%u got=%u)" %
12850
(new_mask, m3.state))
12851
self.progress("correct BUTTON_CHANGE event received")
12852
12853
if self.is_tracker():
12854
# tracker starts armed, which is annoying
12855
self.progress("Skipping arm/disarm tests for tracker")
12856
return
12857
12858
self.context_push()
12859
self.wait_ready_to_arm()
12860
self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM
12861
self.set_parameter("SIM_PIN_MASK", mask)
12862
self.wait_armed()
12863
self.set_parameter("SIM_PIN_MASK", 0)
12864
self.wait_disarmed()
12865
self.context_pop()
12866
12867
if self.is_rover():
12868
self.context_push()
12869
# arming should be inhibited while e-STOP is in use:
12870
# set the function:
12871
self.set_parameter("BTN_FUNC%u" % btn, 31)
12872
# invert the sense of the pin, so eStop is asserted when pin is low:
12873
self.set_parameter("BTN_OPTIONS%u" % btn, 1 << 1)
12874
self.reboot_sitl()
12875
# assert the pin:
12876
self.set_parameter("SIM_PIN_MASK", mask)
12877
self.wait_ready_to_arm()
12878
self.arm_vehicle()
12879
self.disarm_vehicle()
12880
# de-assert the pin:
12881
self.set_parameter("SIM_PIN_MASK", 0)
12882
self.delay_sim_time(1) # 5Hz update rate on Button library
12883
self.context_collect("STATUSTEXT")
12884
# try to arm the vehicle:
12885
self.run_cmd(
12886
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
12887
p1=1, # ARM
12888
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
12889
)
12890
self.assert_prearm_failure("Motors Emergency Stopped",
12891
other_prearm_failures_fatal=False)
12892
self.reboot_sitl()
12893
self.assert_prearm_failure(
12894
"Motors Emergency Stopped",
12895
other_prearm_failures_fatal=False)
12896
self.context_pop()
12897
self.reboot_sitl()
12898
12899
if self.is_rover():
12900
self.start_subtest("Testing using buttons for changing modes")
12901
self.context_push()
12902
if not self.mode_is('MANUAL'):
12903
raise NotAchievedException("Bad mode")
12904
self.set_parameter("BTN_FUNC%u" % btn, 53) # steering mode
12905
# press button:
12906
self.set_parameter("SIM_PIN_MASK", mask)
12907
self.wait_mode('STEERING')
12908
# release button:
12909
self.set_parameter("SIM_PIN_MASK", 0)
12910
self.wait_mode('MANUAL')
12911
self.context_pop()
12912
12913
def compare_number_percent(self, num1, num2, percent):
12914
if num1 == 0 and num2 == 0:
12915
return True
12916
if abs(num1 - num2) / max(abs(num1), abs(num2)) <= percent * 0.01:
12917
return True
12918
return False
12919
12920
def bit_extract(self, number, offset, length):
12921
mask = 0
12922
for i in range(offset, offset+length):
12923
mask |= 1 << i
12924
return (number & mask) >> offset
12925
12926
def tf_encode_gps_latitude(self, lat):
12927
value = 0
12928
if lat < 0:
12929
value = ((abs(lat)//100)*6) | 0x40000000
12930
else:
12931
value = ((abs(lat)//100)*6)
12932
return value
12933
12934
def tf_validate_gps(self, value): # shared by proto 4 and proto 10
12935
self.progress("validating gps (0x%02x)" % value)
12936
lat = value
12937
gpi = self.mav.recv_match(
12938
type='GLOBAL_POSITION_INT',
12939
blocking=True,
12940
timeout=1
12941
)
12942
if gpi is None:
12943
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
12944
gpi_lat = self.tf_encode_gps_latitude(gpi.lat)
12945
self.progress("GLOBAL_POSITION_INT lat==%f frsky==%f" % (gpi_lat, lat))
12946
if gpi_lat == lat:
12947
return True
12948
return False
12949
12950
def tfp_prep_number(self, number, digits, power):
12951
res = 0
12952
abs_number = abs(number)
12953
if digits == 2 and power == 1: # number encoded on 8 bits: 7 bits for digits + 1 for 10^power
12954
if abs_number < 100:
12955
res = abs_number << 1
12956
elif abs_number < 1270:
12957
res = (round(abs_number * 0.1) << 1) | 0x1
12958
else: # transmit max possible value (0x7F x 10^1 = 1270)
12959
res = 0xFF
12960
if number < 0: # if number is negative, add sign bit in front
12961
res |= 0x1 << 8
12962
elif digits == 2 and power == 2: # number encoded on 9 bits: 7 bits for digits + 2 for 10^power
12963
if abs_number < 100:
12964
res = abs_number << 2
12965
elif abs_number < 1000:
12966
res = (round(abs_number * 0.1) << 2) | 0x1
12967
elif abs_number < 10000:
12968
res = (round(abs_number * 0.01) << 2) | 0x2
12969
elif abs_number < 127000:
12970
res = (round(abs_number * 0.001) << 2) | 0x3
12971
else: # transmit max possible value (0x7F x 10^3 = 127000)
12972
res = 0x1FF
12973
if number < 0: # if number is negative, add sign bit in front
12974
res |= 0x1 << 9
12975
elif digits == 3 and power == 1: # number encoded on 11 bits: 10 bits for digits + 1 for 10^power
12976
if abs_number < 1000:
12977
res = abs_number << 1
12978
elif abs_number < 10240:
12979
res = (round(abs_number * 0.1) << 1) | 0x1
12980
else: # transmit max possible value (0x3FF x 10^1 = 10240)
12981
res = 0x7FF
12982
if number < 0: # if number is negative, add sign bit in front
12983
res |= 0x1 << 11
12984
elif digits == 3 and power == 2: # number encoded on 12 bits: 10 bits for digits + 2 for 10^power
12985
if abs_number < 1000:
12986
res = abs_number << 2
12987
elif abs_number < 10000:
12988
res = (round(abs_number * 0.1) << 2) | 0x1
12989
elif abs_number < 100000:
12990
res = (round(abs_number * 0.01) << 2) | 0x2
12991
elif abs_number < 1024000:
12992
res = (round(abs_number * 0.001) << 2) | 0x3
12993
else: # transmit max possible value (0x3FF x 10^3 = 127000)
12994
res = 0xFFF
12995
if number < 0: # if number is negative, add sign bit in front
12996
res |= 0x1 << 12
12997
return res
12998
12999
def tfp_validate_ap_status(self, value): # 0x5001
13000
self.progress("validating ap_status(0x%02x)" % value)
13001
flight_mode = self.bit_extract(value, 0, 5) - 1 # first mode is 1 not 0 :-)
13002
# simple_mode = self.bit_extract(value, 5, 2)
13003
# is_flying = not self.bit_extract(value, 7, 1)
13004
# status_armed = self.bit_extract(value, 8, 1)
13005
# batt_failsafe = self.bit_extract(value, 9, 1)
13006
# ekf_failsafe = self.bit_extract(value, 10, 2)
13007
# imu_temp = self.bit_extract(value, 26, 6) + 19 # IMU temperature: 0 means temp =< 19, 63 means temp => 82
13008
heartbeat = self.wait_heartbeat()
13009
mav_flight_mode = heartbeat.custom_mode
13010
self.progress(" mode=%u heartbeat=%u" % (flight_mode, mav_flight_mode))
13011
if mav_flight_mode == flight_mode:
13012
self.progress("flight mode match")
13013
return True
13014
# FIXME: need to check other values as well
13015
return False
13016
13017
def tfp_validate_attitude(self, value):
13018
self.progress("validating attitude(0x%02x)" % value)
13019
roll = (min(self.bit_extract(value, 0, 11), 1800) - 900) * 0.2 # roll [0,1800] ==> [-180,180]
13020
pitch = (min(self.bit_extract(value, 11, 10), 900) - 450) * 0.2 # pitch [0,900] ==> [-90,90]
13021
# rng_cm = self.bit_extract(value, 22, 10) * (10 ^ self.bit_extract(value, 21, 1)) # cm
13022
atti = self.mav.recv_match(
13023
type='ATTITUDE',
13024
blocking=True,
13025
timeout=1
13026
)
13027
if atti is None:
13028
raise NotAchievedException("Did not get ATTITUDE message")
13029
atti_roll = round(atti.roll)
13030
self.progress("ATTITUDE roll==%f frsky==%f" % (atti_roll, roll))
13031
if abs(atti_roll - roll) >= 5:
13032
return False
13033
atti_pitch = round(atti.pitch)
13034
self.progress("ATTITUDE pitch==%f frsky==%f" % (atti_pitch, pitch))
13035
if abs(atti_pitch - pitch) >= 5:
13036
return False
13037
# FIXME: need to check other values as well
13038
return True
13039
13040
def tfp_validate_home_status(self, value):
13041
self.progress("validating home status(0x%02x)" % value)
13042
# home_dist_m = self.bit_extract(value,2,10) * (10^self.bit_extract(value,0,2))
13043
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
13044
# home_angle_d = self.bit_extract(value, 25, 7) * 3
13045
gpi = self.mav.recv_match(
13046
type='GLOBAL_POSITION_INT',
13047
blocking=True,
13048
timeout=1
13049
)
13050
if gpi is None:
13051
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
13052
gpi_relative_alt_dm = gpi.relative_alt/100.0
13053
self.progress("GLOBAL_POSITION_INT rel_alt==%fm frsky_home_alt==%fm" % (gpi_relative_alt_dm, home_alt_dm))
13054
if abs(gpi_relative_alt_dm - home_alt_dm) < 10:
13055
return True
13056
# FIXME: need to check other values as well
13057
return False
13058
13059
def tfp_validate_gps_status(self, value):
13060
self.progress("validating gps status(0x%02x)" % value)
13061
# num_sats = self.bit_extract(value, 0, 4)
13062
gps_status = self.bit_extract(value, 4, 2) + self.bit_extract(value, 14, 2)
13063
# gps_hdop = self.bit_extract(value, 7, 7) * (10 ^ self.bit_extract(value, 6, 1)) # dm
13064
# 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
13065
gri = self.mav.recv_match(
13066
type='GPS_RAW_INT',
13067
blocking=True,
13068
timeout=1
13069
)
13070
if gri is None:
13071
raise NotAchievedException("Did not get GPS_RAW_INT message")
13072
gri_status = gri.fix_type
13073
self.progress("GPS_RAW_INT fix_type==%f frsky==%f" % (gri_status, gps_status))
13074
if gps_status == gri_status:
13075
return True
13076
# FIXME: need to check other values as well
13077
return False
13078
13079
def tfp_validate_vel_and_yaw(self, value): # 0x5005
13080
self.progress("validating vel_and_yaw(0x%02x)" % value)
13081
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
13082
xy_vel = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))
13083
yaw = self.bit_extract(value, 17, 11) * 0.2
13084
gpi = self.mav.recv_match(
13085
type='GLOBAL_POSITION_INT',
13086
blocking=True,
13087
timeout=1
13088
)
13089
if gpi is None:
13090
return
13091
self.progress(" yaw=%u gpi=%u" % (yaw, gpi.hdg*0.01))
13092
self.progress(" xy_vel=%u" % xy_vel)
13093
self.progress(" z_vel_dm_per_second=%u" % z_vel_dm_per_second)
13094
if self.compare_number_percent(gpi.hdg*0.01, yaw, 10):
13095
self.progress("Yaw match")
13096
return True
13097
# FIXME: need to be under way to check the velocities, really....
13098
return False
13099
13100
def tfp_validate_battery1(self, value):
13101
self.progress("validating battery1 (0x%02x)" % value)
13102
voltage = self.bit_extract(value, 0, 9) # dV
13103
# current = self.bit_extract(value, 10, 7) * (10 ^ self.bit_extract(value, 9, 1))
13104
# mah = self.bit_extract(value, 17, 15)
13105
voltage = value * 0.1
13106
batt = self.mav.recv_match(
13107
type='BATTERY_STATUS',
13108
blocking=True,
13109
timeout=5,
13110
condition="BATTERY_STATUS.id==0"
13111
)
13112
if batt is None:
13113
raise NotAchievedException("Did not get BATTERY_STATUS message")
13114
battery_status_value = batt.voltages[0]*0.001
13115
self.progress("BATTERY_STATUS voltage==%f frsky==%f" % (battery_status_value, voltage))
13116
if abs(battery_status_value - voltage) > 0.1:
13117
return False
13118
# FIXME: need to check other values as well
13119
return True
13120
13121
def tfp_validate_params(self, value):
13122
param_id = self.bit_extract(value, 24, 4)
13123
param_value = self.bit_extract(value, 0, 24)
13124
self.progress("received param (0x%02x) (id=%u value=%u)" %
13125
(value, param_id, param_value))
13126
frame_type = param_value
13127
hb = self.mav.messages['HEARTBEAT']
13128
hb_type = hb.type
13129
self.progress("validate_params: HEARTBEAT type==%f frsky==%f param_id=%u" % (hb_type, frame_type, param_id))
13130
if param_id != 1:
13131
return False
13132
if hb_type == frame_type:
13133
return True
13134
# FIXME: need to check other values as well
13135
return False
13136
13137
def tfp_validate_rpm(self, value):
13138
self.progress("validating rpm (0x%02x)" % value)
13139
tf_rpm = self.bit_extract(value, 0, 16)
13140
rpm = self.mav.recv_match(
13141
type='RPM',
13142
blocking=True,
13143
timeout=5
13144
)
13145
if rpm is None:
13146
raise NotAchievedException("Did not get RPM message")
13147
rpm_value = round(rpm.rpm1 * 0.1)
13148
self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tf_rpm))
13149
if rpm_value != tf_rpm:
13150
return False
13151
return True
13152
13153
def tfp_validate_terrain(self, value):
13154
self.progress("validating terrain(0x%02x)" % value)
13155
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
13156
terrain = self.mav.recv_match(
13157
type='TERRAIN_REPORT',
13158
blocking=True,
13159
timeout=1
13160
)
13161
if terrain is None:
13162
raise NotAchievedException("Did not get TERRAIN_REPORT message")
13163
altitude_terrain_dm = round(terrain.current_height*10)
13164
self.progress("TERRAIN_REPORT terrain_alt==%fdm frsky_terrain_alt==%fdm" % (altitude_terrain_dm, alt_above_terrain_dm))
13165
if abs(altitude_terrain_dm - alt_above_terrain_dm) < 1:
13166
return True
13167
return False
13168
13169
def tfp_validate_wind(self, value):
13170
self.progress("validating wind(0x%02x)" % value)
13171
speed_m = self.bit_extract(value, 8, 7) * (10 ^ self.bit_extract(value, 7, 1)) * 0.1 # speed in m/s
13172
wind = self.mav.recv_match(
13173
type='WIND',
13174
blocking=True,
13175
timeout=1
13176
)
13177
if wind is None:
13178
raise NotAchievedException("Did not get WIND message")
13179
self.progress("WIND mav==%f frsky==%f" % (speed_m, wind.speed))
13180
if abs(speed_m - wind.speed) < 0.5:
13181
return True
13182
return False
13183
13184
def test_frsky_passthrough_do_wants(self, frsky, wants):
13185
13186
tstart = self.get_sim_time_cached()
13187
while len(wants):
13188
self.progress("Still wanting (%s)" % ",".join([("0x%02x" % x) for x in wants.keys()]))
13189
wants_copy = copy.copy(wants)
13190
self.drain_mav()
13191
t2 = self.get_sim_time_cached()
13192
if t2 - tstart > 300:
13193
self.progress("Failed to get frsky passthrough data")
13194
self.progress("Counts of sensor_id polls sent:")
13195
frsky.dump_sensor_id_poll_counts_as_progress_messages()
13196
self.progress("Counts of dataids received:")
13197
frsky.dump_dataid_counts_as_progress_messages()
13198
raise AutoTestTimeoutException("Failed to get frsky passthrough data")
13199
frsky.update()
13200
for want in wants_copy:
13201
data = frsky.get_data(want)
13202
if data is None:
13203
continue
13204
self.progress("Checking 0x%x" % (want,))
13205
if wants[want](data):
13206
self.progress(" Fulfilled")
13207
del wants[want]
13208
13209
def FRSkyPassThroughStatustext(self):
13210
'''test FRSKy protocol's telem-passthrough functionality'''
13211
# we disable terrain here as RCTelemetry can queue a lot of
13212
# statustexts if terrain tiles aren't available which can
13213
# happen on the autotest server.
13214
self.set_parameters({
13215
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
13216
"RPM1_TYPE": 10, # enable RPM output
13217
"TERRAIN_ENABLE": 0,
13218
})
13219
port = self.spare_network_port()
13220
self.customise_SITL_commandline([
13221
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13222
])
13223
frsky = FRSkyPassThrough(("127.0.0.1", port),
13224
get_time=self.get_sim_time_cached)
13225
13226
# waiting until we are ready to arm should ensure our wanted
13227
# statustext doesn't get blatted out of the ArduPilot queue by
13228
# random messages.
13229
self.wait_ready_to_arm()
13230
13231
# test we get statustext strings. This relies on ArduPilot
13232
# emitting statustext strings when we fetch parameters. (or,
13233
# now, an updating-barometer statustext)
13234
tstart = self.get_sim_time()
13235
old_data = None
13236
text = ""
13237
13238
self.context_collect('STATUSTEXT')
13239
command = mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION
13240
self.send_cmd(
13241
command,
13242
p3=1, # p3, baro
13243
)
13244
# this is a test for asynchronous handling of mavlink messages:
13245
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_IN_PROGRESS, 2)
13246
self.run_cmd_get_ack(command, mavutil.mavlink.MAV_RESULT_ACCEPTED, 5)
13247
13248
received_frsky_texts = []
13249
last_len_received_statustexts = 0
13250
timeout = 7 * self.speedup # it can take a *long* time to get these messages down!
13251
while True:
13252
self.drain_mav()
13253
now = self.get_sim_time_cached()
13254
if now - tstart > timeout:
13255
raise NotAchievedException("Did not get statustext in time")
13256
frsky.update()
13257
data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats.
13258
if data is None:
13259
continue
13260
# frsky sends each quartet three times; skip the suplicates.
13261
if old_data is not None and old_data == data:
13262
continue
13263
old_data = data
13264
self.progress("Got (0x%x)" % data)
13265
severity = 0
13266
last = False
13267
for i in 3, 2, 1, 0:
13268
x = (data >> i*8) & 0xff
13269
text += chr(x & 0x7f)
13270
self.progress(" x=0x%02x" % x)
13271
if x & 0x80:
13272
severity += 1 << i
13273
self.progress("Text sev=%u: %s" % (severity, str(text)))
13274
if (x & 0x7f) == 0x00:
13275
last = True
13276
if last:
13277
m = None
13278
text = text.rstrip("\0")
13279
self.progress("Received frsky text (%s)" % (text,))
13280
self.progress("context texts: %s" %
13281
str([st.text for st in self.context_collection('STATUSTEXT')]))
13282
m = self.statustext_in_collections(text)
13283
if m is not None:
13284
want_sev = m.severity
13285
if severity != want_sev:
13286
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
13287
self.progress("Got statustext (%s)" % m.text)
13288
break
13289
received_frsky_texts.append((severity, text))
13290
text = ""
13291
received_statustexts = self.context_collection('STATUSTEXT')
13292
if len(received_statustexts) != last_len_received_statustexts:
13293
last_len_received_statustexts = len(received_statustexts)
13294
self.progress("received statustexts: %s" % str([st.text for st in received_statustexts]))
13295
self.progress("received frsky texts: %s" % str(received_frsky_texts))
13296
for (want_sev, received_text) in received_frsky_texts:
13297
for m in received_statustexts:
13298
if m.text == received_text:
13299
if want_sev != m.severity:
13300
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
13301
self.progress("Got statustext (%s)" % received_text)
13302
break
13303
13304
def FRSkyPassThroughSensorIDs(self):
13305
'''test FRSKy protocol's telem-passthrough functionality (sensor IDs)'''
13306
self.set_parameters({
13307
"SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough
13308
"RPM1_TYPE": 10, # enable RPM output
13309
})
13310
port = self.spare_network_port()
13311
self.customise_SITL_commandline([
13312
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13313
])
13314
frsky = FRSkyPassThrough(("127.0.0.1", port),
13315
get_time=self.get_sim_time_cached)
13316
13317
self.wait_ready_to_arm()
13318
13319
# we need to start the engine to get some RPM readings, we do it for plane only
13320
# anything with a lambda in here needs a proper test written.
13321
# This, at least makes sure we're getting some of each
13322
# message. These are ordered according to the wfq scheduler
13323
wants = {
13324
0x5000: lambda xx: True,
13325
0x5006: self.tfp_validate_attitude,
13326
0x0800: self.tf_validate_gps,
13327
0x5005: self.tfp_validate_vel_and_yaw,
13328
0x5001: self.tfp_validate_ap_status,
13329
0x5002: self.tfp_validate_gps_status,
13330
0x5004: self.tfp_validate_home_status,
13331
# 0x5008: lambda x : True, # no second battery, so this doesn't arrive
13332
0x5003: self.tfp_validate_battery1,
13333
0x5007: self.tfp_validate_params,
13334
0x500B: self.tfp_validate_terrain,
13335
0x500C: self.tfp_validate_wind,
13336
}
13337
self.test_frsky_passthrough_do_wants(frsky, wants)
13338
13339
# now check RPM:
13340
if self.is_plane():
13341
self.set_autodisarm_delay(0)
13342
if not self.arm_vehicle():
13343
raise NotAchievedException("Failed to ARM")
13344
self.set_rc(3, 1050)
13345
wants = {
13346
0x500A: self.tfp_validate_rpm,
13347
}
13348
self.test_frsky_passthrough_do_wants(frsky, wants)
13349
self.zero_throttle()
13350
self.progress("Wait for vehicle to slow down")
13351
self.wait_groundspeed(0, 0.3)
13352
self.disarm_vehicle()
13353
13354
self.progress("Counts of sensor_id polls sent:")
13355
frsky.dump_sensor_id_poll_counts_as_progress_messages()
13356
self.progress("Counts of dataids received:")
13357
frsky.dump_dataid_counts_as_progress_messages()
13358
13359
def decode_mavlite_param_value(self, message):
13360
'''returns a tuple of parameter name, value'''
13361
(value,) = struct.unpack("<f", message[0:4])
13362
name = message[4:]
13363
return (name, value)
13364
13365
def decode_mavlite_command_ack(self, message):
13366
'''returns a tuple of parameter name, value'''
13367
(command, result) = struct.unpack("<HB", message)
13368
return (command, result)
13369
13370
def read_message_via_mavlite(self, frsky, sport_to_mavlite):
13371
'''read bytes from frsky mavlite stream, trying to form up a mavlite
13372
message'''
13373
tstart = self.get_sim_time()
13374
timeout = 30 * self.speedup/10.0
13375
if self.valgrind or self.callgrind:
13376
timeout *= 10
13377
while True:
13378
self.drain_mav(quiet=True)
13379
tnow = self.get_sim_time_cached()
13380
if tnow - tstart > timeout:
13381
raise NotAchievedException("Did not get parameter via mavlite")
13382
frsky.update()
13383
if sport_to_mavlite.state == sport_to_mavlite.state_MESSAGE_RECEIVED:
13384
message = sport_to_mavlite.get_message()
13385
sport_to_mavlite.reset()
13386
# self.progress("############ message received (type=%u)" % message.msgid)
13387
return message
13388
13389
def read_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):
13390
tstart = self.get_sim_time()
13391
while True:
13392
tnow = self.get_sim_time_cached()
13393
if tnow - tstart > 30 * self.speedup / 10.0:
13394
raise NotAchievedException("Did not get parameter via mavlite")
13395
message = self.read_message_via_mavlite(frsky, sport_to_mavlite)
13396
if message.msgid != mavutil.mavlink.MAVLINK_MSG_ID_PARAM_VALUE:
13397
raise NotAchievedException("Unexpected msgid %u received" % message.msgid)
13398
(got_name, value) = self.decode_mavlite_param_value(message.body)
13399
# self.progress("Received parameter: %s=%f" % (name, value))
13400
got_name = got_name.decode('ascii')
13401
if got_name != name:
13402
raise NotAchievedException("Incorrect name received (want=%s) (got=%s)" % (name, got_name))
13403
return value
13404
13405
def get_parameter_via_mavlite(self, frsky, sport_to_mavlite, name):
13406
# self.progress("########## Sending request")
13407
frsky.send_mavlite_param_request_read(name)
13408
return self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)
13409
13410
def set_parameter_via_mavlite(self, frsky, sport_to_mavlite, name, value):
13411
# self.progress("########## Sending request")
13412
frsky.send_mavlite_param_set(name, value)
13413
# new value is echoed back immediately:
13414
got_val = self.read_parameter_via_mavlite(frsky, sport_to_mavlite, name)
13415
if abs(got_val - value) > 0.00001:
13416
raise NotAchievedException("Returned value not same as set value (want=%f got=%f)" % (value, got_val))
13417
13418
def run_cmd_via_mavlite(self,
13419
frsky,
13420
sport_to_mavlite,
13421
command,
13422
p1=None,
13423
p2=None,
13424
p3=None,
13425
p4=None,
13426
p5=None,
13427
p6=None,
13428
p7=None,
13429
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED):
13430
frsky.send_mavlite_command_long(
13431
command,
13432
p1=p1,
13433
p2=p2,
13434
p3=p3,
13435
p4=p4,
13436
p5=p5,
13437
p6=p6,
13438
p7=p7,
13439
)
13440
self.run_cmd_via_mavlite_get_ack(
13441
frsky,
13442
sport_to_mavlite,
13443
command,
13444
want_result
13445
)
13446
13447
def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_result):
13448
'''expect and read a command-ack from frsky sport passthrough'''
13449
msg = self.read_message_via_mavlite(frsky, sport_to_mavlite)
13450
if msg.msgid != mavutil.mavlink.MAVLINK_MSG_ID_COMMAND_ACK:
13451
raise NotAchievedException("Expected a command-ack, got a %u" % msg.msgid)
13452
(got_command, got_result) = self.decode_mavlite_command_ack(msg.body)
13453
if got_command != command:
13454
raise NotAchievedException(
13455
"Did not receive expected command in command_ack; want=%u got=%u" %
13456
(command, got_command))
13457
if got_result != want_result:
13458
raise NotAchievedException(
13459
"Did not receive expected result in command_ack; want=%u got=%u" %
13460
(want_result, got_result))
13461
13462
def FRSkyMAVlite(self):
13463
'''Test FrSky MAVlite serial output'''
13464
self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough
13465
port = self.spare_network_port()
13466
self.customise_SITL_commandline([
13467
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13468
])
13469
frsky = FRSkyPassThrough(("127.0.0.1", port))
13470
frsky.connect()
13471
13472
sport_to_mavlite = SPortToMAVlite()
13473
frsky.data_downlink_handler = sport_to_mavlite.downlink_handler
13474
13475
self.start_subtest("Get parameter via MAVlite")
13476
param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles
13477
set_value = 97.21
13478
self.set_parameter(param_name, set_value) # DO NOT FLY
13479
got_value = self.get_parameter_via_mavlite(frsky,
13480
sport_to_mavlite,
13481
param_name)
13482
if abs(got_value - set_value) > 0.00001:
13483
raise NotAchievedException("Incorrect value retrieved via mavlite (want=%f got=%f)" % (set_value, got_value))
13484
self.progress("Got value OK")
13485
self.end_subtest("Get parameter via MAVlite")
13486
13487
self.start_subtest("Set parameter via MAVlite")
13488
param_name = "STAB_PITCH_DOWN" # FIXME: want common across vehicles
13489
set_value = 91.67
13490
# frsky.verbose = True
13491
self.set_parameter_via_mavlite(frsky, sport_to_mavlite, param_name, set_value) # DO NOT FLY
13492
got_value = self.get_parameter(param_name)
13493
if abs(got_value - set_value) > 0.00001:
13494
raise NotAchievedException("Incorrect value retrieved via mavlink (want=%f got=%f)" % (set_value, got_value))
13495
self.progress("Set value OK")
13496
self.end_subtest("Set parameter via MAVlite")
13497
13498
self.start_subtest("Calibrate Baro via MAVLite")
13499
self.context_push()
13500
self.context_collect("STATUSTEXT")
13501
self.run_cmd_via_mavlite(
13502
frsky,
13503
sport_to_mavlite,
13504
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
13505
p1=0,
13506
p2=0,
13507
p3=1.0,
13508
)
13509
self.wait_statustext("Updating barometer calibration", check_context=True)
13510
self.context_pop()
13511
self.end_subtest("Calibrate Baro via MAVLite")
13512
13513
self.start_subtest("Change mode via MAVLite")
13514
# FIXME: currently plane-specific
13515
self.run_cmd_via_mavlite(
13516
frsky,
13517
sport_to_mavlite,
13518
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
13519
p1=mavutil.mavlink.PLANE_MODE_MANUAL,
13520
)
13521
self.wait_mode("MANUAL")
13522
self.run_cmd_via_mavlite(
13523
frsky,
13524
sport_to_mavlite,
13525
mavutil.mavlink.MAV_CMD_DO_SET_MODE,
13526
p1=mavutil.mavlink.PLANE_MODE_FLY_BY_WIRE_A,
13527
)
13528
self.wait_mode("FBWA")
13529
self.end_subtest("Change mode via MAVLite")
13530
13531
self.start_subtest("Enable fence via MAVlite")
13532
# Fence can be enabled using MAV_CMD
13533
self.run_cmd_via_mavlite(
13534
frsky,
13535
sport_to_mavlite,
13536
mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE,
13537
p1=1,
13538
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED,
13539
)
13540
self.end_subtest("Enable fence via MAVlite")
13541
13542
def tfs_validate_gps_alt(self, value):
13543
self.progress("validating gps altitude (0x%02x)" % value)
13544
alt_m = value * 0.01 # cm -> m
13545
gpi = self.mav.recv_match(
13546
type='GLOBAL_POSITION_INT',
13547
blocking=True,
13548
timeout=1
13549
)
13550
if gpi is None:
13551
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
13552
gpi_alt_m = round(gpi.alt * 0.001) # mm-> m
13553
self.progress("GLOBAL_POSITION_INT alt==%f frsky==%f" % (gpi_alt_m, alt_m))
13554
if self.compare_number_percent(gpi_alt_m, alt_m, 10):
13555
return True
13556
return False
13557
13558
def tfs_validate_baro_alt(self, value):
13559
self.progress("validating baro altitude (0x%02x)" % value)
13560
alt_m = value * 0.01 # cm -> m
13561
gpi = self.mav.recv_match(
13562
type='GLOBAL_POSITION_INT',
13563
blocking=True,
13564
timeout=1
13565
)
13566
if gpi is None:
13567
raise NotAchievedException("Did not get GLOBAL_POSITION_INT message")
13568
gpi_alt_m = round(gpi.relative_alt * 0.001) # mm -> m
13569
self.progress("GLOBAL_POSITION_INT relative_alt==%f frsky==%f" % (gpi_alt_m, alt_m))
13570
if abs(gpi_alt_m - alt_m) < 1:
13571
return True
13572
return False
13573
13574
def tfs_validate_gps_speed(self, value):
13575
self.progress("validating gps speed (0x%02x)" % value)
13576
speed_ms = value * 0.001 # mm/s -> m/s
13577
vfr_hud = self.mav.recv_match(
13578
type='VFR_HUD',
13579
blocking=True,
13580
timeout=1
13581
)
13582
if vfr_hud is None:
13583
raise NotAchievedException("Did not get VFR_HUD message")
13584
vfr_hud_speed_ms = round(vfr_hud.groundspeed)
13585
self.progress("VFR_HUD groundspeed==%f frsky==%f" % (vfr_hud_speed_ms, speed_ms))
13586
if self.compare_number_percent(vfr_hud_speed_ms, speed_ms, 10):
13587
return True
13588
return False
13589
13590
def tfs_validate_yaw(self, value):
13591
self.progress("validating yaw (0x%02x)" % value)
13592
yaw_deg = value * 0.01 # cd -> deg
13593
vfr_hud = self.mav.recv_match(
13594
type='VFR_HUD',
13595
blocking=True,
13596
timeout=1
13597
)
13598
if vfr_hud is None:
13599
raise NotAchievedException("Did not get VFR_HUD message")
13600
vfr_hud_yaw_deg = round(vfr_hud.heading)
13601
self.progress("VFR_HUD heading==%f frsky==%f" % (vfr_hud_yaw_deg, yaw_deg))
13602
if self.compare_number_percent(vfr_hud_yaw_deg, yaw_deg, 10):
13603
return True
13604
return False
13605
13606
def tfs_validate_vspeed(self, value):
13607
self.progress("validating vspeed (0x%02x)" % value)
13608
vspeed_ms = value * 0.01 # cm/s -> m/s
13609
vfr_hud = self.mav.recv_match(
13610
type='VFR_HUD',
13611
blocking=True,
13612
timeout=1
13613
)
13614
if vfr_hud is None:
13615
raise NotAchievedException("Did not get VFR_HUD message")
13616
vfr_hud_vspeed_ms = round(vfr_hud.climb)
13617
self.progress("VFR_HUD climb==%f frsky==%f" % (vfr_hud_vspeed_ms, vspeed_ms))
13618
if self.compare_number_percent(vfr_hud_vspeed_ms, vspeed_ms, 10):
13619
return True
13620
return False
13621
13622
def tfs_validate_battery1(self, value):
13623
self.progress("validating battery1 (0x%02x)" % value)
13624
voltage_v = value * 0.01 # cV -> V
13625
batt = self.mav.recv_match(
13626
type='BATTERY_STATUS',
13627
blocking=True,
13628
timeout=5,
13629
condition="BATTERY_STATUS.id==0"
13630
)
13631
if batt is None:
13632
raise NotAchievedException("Did not get BATTERY_STATUS message")
13633
battery_status_voltage_v = batt.voltages[0] * 0.001 # mV -> V
13634
self.progress("BATTERY_STATUS volatge==%f frsky==%f" % (battery_status_voltage_v, voltage_v))
13635
if self.compare_number_percent(battery_status_voltage_v, voltage_v, 10):
13636
return True
13637
return False
13638
13639
def tfs_validate_current1(self, value):
13640
# test frsky current vs BATTERY_STATUS
13641
self.progress("validating battery1 (0x%02x)" % value)
13642
current_a = value * 0.1 # dA -> A
13643
batt = self.mav.recv_match(
13644
type='BATTERY_STATUS',
13645
blocking=True,
13646
timeout=5,
13647
condition="BATTERY_STATUS.id==0"
13648
)
13649
if batt is None:
13650
raise NotAchievedException("Did not get BATTERY_STATUS message")
13651
battery_status_current_a = batt.current_battery * 0.01 # cA -> A
13652
self.progress("BATTERY_STATUS current==%f frsky==%f" % (battery_status_current_a, current_a))
13653
if self.compare_number_percent(round(battery_status_current_a * 10), round(current_a * 10), 10):
13654
return True
13655
return False
13656
13657
def tfs_validate_fuel(self, value):
13658
self.progress("validating fuel (0x%02x)" % value)
13659
fuel = value
13660
batt = self.mav.recv_match(
13661
type='BATTERY_STATUS',
13662
blocking=True,
13663
timeout=5,
13664
condition="BATTERY_STATUS.id==0"
13665
)
13666
if batt is None:
13667
raise NotAchievedException("Did not get BATTERY_STATUS message")
13668
battery_status_fuel = batt.battery_remaining
13669
self.progress("BATTERY_STATUS fuel==%f frsky==%f" % (battery_status_fuel, fuel))
13670
if self.compare_number_percent(battery_status_fuel, fuel, 10):
13671
return True
13672
return False
13673
13674
def tfs_validate_tmp1(self, value):
13675
self.progress("validating tmp1 (0x%02x)" % value)
13676
tmp1 = value
13677
heartbeat = self.wait_heartbeat()
13678
heartbeat_tmp1 = heartbeat.custom_mode
13679
self.progress("GLOBAL_POSITION_INT custom_mode==%f frsky==%f" % (heartbeat_tmp1, tmp1))
13680
if heartbeat_tmp1 == tmp1:
13681
return True
13682
return False
13683
13684
def tfs_validate_tmp2(self, value):
13685
self.progress("validating tmp2 (0x%02x)" % value)
13686
tmp2 = value
13687
gps_raw = self.mav.recv_match(
13688
type='GPS_RAW_INT',
13689
blocking=True,
13690
timeout=1
13691
)
13692
if gps_raw is None:
13693
raise NotAchievedException("Did not get GPS_RAW_INT message")
13694
gps_raw_tmp2 = gps_raw.satellites_visible*10 + gps_raw.fix_type
13695
self.progress("GPS_RAW_INT tmp2==%f frsky==%f" % (gps_raw_tmp2, tmp2))
13696
if gps_raw_tmp2 == tmp2:
13697
return True
13698
return False
13699
13700
def tfs_validate_rpm(self, value):
13701
self.progress("validating rpm (0x%02x)" % value)
13702
tfs_rpm = value
13703
rpm = self.mav.recv_match(
13704
type='RPM',
13705
blocking=True,
13706
timeout=5
13707
)
13708
if rpm is None:
13709
raise NotAchievedException("Did not get RPM message")
13710
rpm_value = round(rpm.rpm1)
13711
self.progress("RPM rpm==%f frsky==%f" % (rpm_value, tfs_rpm))
13712
if rpm_value == tfs_rpm:
13713
return True
13714
return False
13715
13716
def wait_rpm1(self, min_rpm=None, timeout=10):
13717
'''wait for mavlink RPM message to indicate valid RPM'''
13718
tstart = self.get_sim_time()
13719
while True:
13720
t = self.get_sim_time_cached()
13721
if t - tstart > timeout:
13722
raise AutoTestTimeoutException("Failed to do get valid RPM")
13723
rpm = self.mav.recv_match(
13724
type='RPM',
13725
blocking=True,
13726
timeout=1
13727
)
13728
self.progress("rpm: (%s)" % str(rpm))
13729
if rpm is None:
13730
continue
13731
if min_rpm is None:
13732
return
13733
if rpm.rpm1 >= min_rpm:
13734
return
13735
13736
def FRSkySPort(self):
13737
'''Test FrSky SPort mode'''
13738
self.set_parameters({
13739
"SERIAL5_PROTOCOL": 4, # serial5 is FRSky sport
13740
"RPM1_TYPE": 10, # enable SITL RPM sensor
13741
"GPS1_TYPE": 100, # use simulated backend for consistent position
13742
})
13743
port = self.spare_network_port()
13744
self.customise_SITL_commandline([
13745
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13746
])
13747
frsky = FRSkySPort(("127.0.0.1", port), verbose=True)
13748
self.wait_ready_to_arm()
13749
13750
# we need to start the engine to get some RPM readings, we do it for plane only
13751
if self.is_plane():
13752
self.set_autodisarm_delay(0)
13753
if not self.arm_vehicle():
13754
raise NotAchievedException("Failed to ARM")
13755
self.set_rc(3, 1050)
13756
self.wait_rpm1(timeout=10, min_rpm=200)
13757
13758
self.assert_current_onboard_log_contains_message("RPM")
13759
13760
self.drain_mav()
13761
# anything with a lambda in here needs a proper test written.
13762
# This, at least makes sure we're getting some of each
13763
# message.
13764
wants = {
13765
0x082F: self.tfs_validate_gps_alt, # gps altitude integer cm
13766
0x040F: self.tfs_validate_tmp1, # Tmp1
13767
0x060F: self.tfs_validate_fuel, # fuel % 0-100
13768
0x041F: self.tfs_validate_tmp2, # Tmp2
13769
0x010F: self.tfs_validate_baro_alt, # baro alt cm
13770
0x083F: self.tfs_validate_gps_speed, # gps speed integer mm/s
13771
0x084F: self.tfs_validate_yaw, # yaw in cd
13772
0x020F: self.tfs_validate_current1, # current dA
13773
0x011F: self.tfs_validate_vspeed, # vertical speed cm/s
13774
0x021F: self.tfs_validate_battery1, # battery 1 voltage cV
13775
0x0800: self.tf_validate_gps, # gps lat/lon
13776
0x050E: self.tfs_validate_rpm, # rpm 1
13777
}
13778
tstart = self.get_sim_time_cached()
13779
last_wanting_print = 0
13780
13781
last_data_time = None
13782
while len(wants):
13783
now = self.get_sim_time()
13784
if now - last_wanting_print > 1:
13785
self.progress("Still wanting (%s)" %
13786
",".join([("0x%02x" % x) for x in wants.keys()]))
13787
last_wanting_print = now
13788
wants_copy = copy.copy(wants)
13789
if now - tstart > 300:
13790
self.progress("Failed to get frsky passthrough data")
13791
self.progress("Counts of sensor_id polls sent:")
13792
frsky.dump_sensor_id_poll_counts_as_progress_messages()
13793
self.progress("Counts of dataids received:")
13794
frsky.dump_dataid_counts_as_progress_messages()
13795
raise AutoTestTimeoutException("Failed to get frsky sport data")
13796
frsky.update()
13797
if frsky.last_data_time == last_data_time:
13798
continue
13799
last_data_time = frsky.last_data_time
13800
for want in wants_copy:
13801
data = frsky.get_data(want)
13802
if data is None:
13803
continue
13804
self.progress("Checking 0x%x" % (want,))
13805
if wants[want](data):
13806
self.progress(" Fulfilled")
13807
del wants[want]
13808
# ok done, stop the engine
13809
if self.is_plane():
13810
self.zero_throttle()
13811
self.disarm_vehicle(force=True)
13812
13813
def FRSkyD(self):
13814
'''Test FrSkyD serial output'''
13815
self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output
13816
port = self.spare_network_port()
13817
self.customise_SITL_commandline([
13818
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13819
])
13820
frsky = FRSkyD(("127.0.0.1", port))
13821
self.wait_ready_to_arm()
13822
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)
13823
gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m
13824
13825
# grab a battery-remaining percentage
13826
self.run_cmd(
13827
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
13828
p1=65535, # battery mask
13829
p2=96, # percentage
13830
)
13831
m = self.assert_receive_message('BATTERY_STATUS', timeout=1)
13832
want_battery_remaining_pct = m.battery_remaining
13833
13834
tstart = self.get_sim_time_cached()
13835
have_alt = False
13836
have_battery = False
13837
while True:
13838
t2 = self.get_sim_time_cached()
13839
if t2 - tstart > 10:
13840
raise AutoTestTimeoutException("Failed to get frsky D data")
13841
frsky.update()
13842
13843
alt = frsky.get_data(frsky.dataid_GPS_ALT_BP)
13844
self.progress("Got alt (%s) mav=%s" % (str(alt), str(gpi_abs_alt)))
13845
if alt is None:
13846
continue
13847
if alt == gpi_abs_alt:
13848
have_alt = True
13849
13850
batt = frsky.get_data(frsky.dataid_FUEL)
13851
self.progress("Got batt (%s) mav=%s" % (str(batt), str(want_battery_remaining_pct)))
13852
if batt is None:
13853
continue
13854
if batt == want_battery_remaining_pct:
13855
have_battery = True
13856
13857
if have_alt and have_battery:
13858
break
13859
self.drain_mav()
13860
13861
def test_ltm_g(self, ltm):
13862
g = ltm.g()
13863
if g is None:
13864
return
13865
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
13866
print("m: %s" % str(m))
13867
13868
print("g.lat=%s m.lat=%s" % (str(g.lat()), str(m.lat)))
13869
if abs(m.lat - g.lat()) > 10:
13870
return False
13871
13872
print("g.lon:%s m.lon:%s" % (str(g.lon()), str(m.lon)))
13873
if abs(m.lon - g.lon()) > 10:
13874
return False
13875
13876
print("gndspeed: %s" % str(g.gndspeed()))
13877
if g.gndspeed() != 0:
13878
# FIXME if we start the vehicle moving.... check against VFR_HUD?
13879
return False
13880
13881
print("g.alt=%s m.alt=%s" % (str(g.alt()/100.0), str(m.relative_alt/1000.0)))
13882
if abs(m.relative_alt/1000.0 - g.alt()/100.0) > 1:
13883
return False
13884
13885
print("sats: %s" % str(g.sats()))
13886
m = self.mav.recv_match(type='GPS_RAW_INT', blocking=True)
13887
if m.satellites_visible != g.sats():
13888
return False
13889
13890
constrained_fix_type = m.fix_type
13891
if constrained_fix_type > 3:
13892
constrained_fix_type = 3
13893
print("fix_type: %s" % g.fix_type())
13894
if constrained_fix_type != g.fix_type():
13895
return False
13896
13897
return True
13898
13899
def test_ltm_a(self, ltm):
13900
a = ltm.a()
13901
if a is None:
13902
return
13903
m = self.assert_receive_message('ATTITUDE')
13904
13905
pitch = a.pitch()
13906
print("pitch: %s" % str(pitch))
13907
if abs(math.degrees(m.pitch) - pitch) > 1:
13908
return False
13909
13910
roll = a.roll()
13911
print("roll: %s" % str(roll))
13912
if abs(math.degrees(m.roll) - roll) > 1:
13913
return False
13914
13915
hdg = a.hdg()
13916
myaw = math.degrees(m.yaw)
13917
myaw += 360
13918
myaw %= 360
13919
print("a.hdg=%s m.hdg=%s" % (str(hdg), str(myaw)))
13920
if abs(myaw - hdg) > 1:
13921
return False
13922
13923
return True
13924
13925
def test_ltm_s(self, ltm):
13926
s = ltm.s()
13927
if s is None:
13928
return
13929
# FIXME. Actually check the field values are correct :-)
13930
return True
13931
13932
def LTM(self):
13933
'''Test LTM serial output'''
13934
self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output
13935
port = self.spare_network_port()
13936
self.customise_SITL_commandline([
13937
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13938
])
13939
ltm = LTM(("127.0.0.1", port))
13940
self.wait_ready_to_arm()
13941
13942
wants = {
13943
"g": self.test_ltm_g,
13944
"a": self.test_ltm_a,
13945
"s": self.test_ltm_s,
13946
}
13947
13948
tstart = self.get_sim_time()
13949
while True:
13950
self.progress("Still wanting (%s)" %
13951
",".join([("%s" % x) for x in wants.keys()]))
13952
if len(wants) == 0:
13953
break
13954
now = self.get_sim_time_cached()
13955
if now - tstart > 10:
13956
raise AutoTestTimeoutException("Failed to get ltm data")
13957
13958
ltm.update()
13959
13960
wants_copy = copy.copy(wants)
13961
for want in wants_copy:
13962
self.progress("Checking %s" % (want,))
13963
if wants[want](ltm):
13964
self.progress(" Fulfilled")
13965
del wants[want]
13966
13967
def convertDmsToDdFormat(self, dms):
13968
deg = math.trunc(dms * 1e-7)
13969
dd = deg + (((dms * 1.0e-7) - deg) * 100.0 / 60.0)
13970
if dd < -180.0 or dd > 180.0:
13971
dd = 0.0
13972
return math.trunc(dd * 1.0e7)
13973
13974
def DEVO(self):
13975
'''Test DEVO serial output'''
13976
self.context_push()
13977
self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output
13978
port = self.spare_network_port()
13979
self.customise_SITL_commandline([
13980
"--serial5=tcp:%u" % port # serial5 spews to localhost port
13981
])
13982
devo = DEVO(("127.0.0.1", port))
13983
self.wait_ready_to_arm()
13984
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)
13985
13986
tstart = self.get_sim_time_cached()
13987
while True:
13988
self.drain_mav()
13989
now = self.get_sim_time_cached()
13990
if now - tstart > 10:
13991
if devo.frame is not None:
13992
# we received some frames but could not find correct values
13993
raise AutoTestTimeoutException("Failed to get correct data")
13994
else:
13995
# No frames received. Devo telemetry is compiled out?
13996
break
13997
13998
devo.update()
13999
frame = devo.frame
14000
if frame is None:
14001
continue
14002
14003
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
14004
14005
loc = LocationInt(self.convertDmsToDdFormat(frame.lat()), self.convertDmsToDdFormat(frame.lon()), 0, 0)
14006
14007
print("received lat:%s expected lat:%s" % (str(loc.lat), str(m.lat)))
14008
print("received lon:%s expected lon:%s" % (str(loc.lon), str(m.lon)))
14009
dist_diff = self.get_distance_int(loc, m)
14010
print("Distance:%s" % str(dist_diff))
14011
if abs(dist_diff) > 2:
14012
continue
14013
14014
gpi_rel_alt = int(m.relative_alt / 10) # mm -> cm, since driver send alt in cm
14015
print("received alt:%s expected alt:%s" % (str(frame.alt()), str(gpi_rel_alt)))
14016
if abs(gpi_rel_alt - frame.alt()) > 10:
14017
continue
14018
14019
print("received gndspeed: %s" % str(frame.speed()))
14020
if frame.speed() != 0:
14021
# FIXME if we start the vehicle moving.... check against VFR_HUD?
14022
continue
14023
14024
print("received temp:%s expected temp:%s" % (str(frame.temp()), str(self.mav.messages['HEARTBEAT'].custom_mode)))
14025
if frame.temp() != self.mav.messages['HEARTBEAT'].custom_mode:
14026
# currently we receive mode as temp. This should be fixed when driver is updated
14027
continue
14028
14029
# we match the received voltage with the voltage of primary instance
14030
batt = self.mav.recv_match(
14031
type='BATTERY_STATUS',
14032
blocking=True,
14033
timeout=5,
14034
condition="BATTERY_STATUS.id==0"
14035
)
14036
if batt is None:
14037
raise NotAchievedException("Did not get BATTERY_STATUS message")
14038
volt = batt.voltages[0]*0.001
14039
print("received voltage:%s expected voltage:%s" % (str(frame.volt()*0.1), str(volt)))
14040
if abs(frame.volt()*0.1 - volt) > 0.1:
14041
continue
14042
# if we reach here, exit
14043
break
14044
self.context_pop()
14045
self.reboot_sitl()
14046
14047
def MSP_DJI(self):
14048
'''Test MSP DJI serial output'''
14049
self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output
14050
self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode
14051
port = self.spare_network_port()
14052
self.customise_SITL_commandline([
14053
"--serial5=tcp:%u" % port # serial5 spews to localhost port
14054
])
14055
msp = MSP_DJI(("127.0.0.1", port))
14056
self.wait_ready_to_arm()
14057
14058
tstart = self.get_sim_time()
14059
while True:
14060
self.drain_mav()
14061
if self.get_sim_time_cached() - tstart > 10:
14062
raise NotAchievedException("Did not get location")
14063
msp.update()
14064
try:
14065
f = msp.get_frame(msp.FRAME_GPS_RAW)
14066
except KeyError:
14067
continue
14068
dist = self.get_distance_int(f.LocationInt(), self.sim_location_int())
14069
print("lat=%f lon=%f dist=%f" % (f.lat(), f.lon(), dist))
14070
if dist < 1:
14071
break
14072
14073
def CRSF(self):
14074
'''Test RC CRSF'''
14075
self.context_push()
14076
ex = None
14077
try:
14078
self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input
14079
port = self.spare_network_port()
14080
self.customise_SITL_commandline([
14081
"--serial5=tcp:%u" % port # serial5 reads from to localhost port
14082
])
14083
crsf = CRSF(("127.0.0.1", port))
14084
crsf.connect()
14085
14086
self.progress("Writing vtx_frame")
14087
crsf.write_data_id(crsf.dataid_vtx_frame)
14088
self.delay_sim_time(5)
14089
self.progress("Writing vtx_telem")
14090
crsf.write_data_id(crsf.dataid_vtx_telem)
14091
self.delay_sim_time(5)
14092
self.progress("Writing vtx_unknown")
14093
crsf.write_data_id(crsf.dataid_vtx_unknown)
14094
self.delay_sim_time(5)
14095
except Exception as e:
14096
self.print_exception_caught(e)
14097
ex = e
14098
self.context_pop()
14099
self.disarm_vehicle(force=True)
14100
self.reboot_sitl()
14101
if ex is not None:
14102
raise ex
14103
14104
def CompassPrearms(self):
14105
'''test compass prearm checks'''
14106
self.wait_ready_to_arm()
14107
# XY are checked specially:
14108
for axis in 'X', 'Y': # ArduPilot only checks these two axes
14109
self.context_push()
14110
self.set_parameter(f"COMPASS_OFS2_{axis}", 1000)
14111
self.assert_prearm_failure("Compasses inconsistent")
14112
self.context_pop()
14113
self.wait_ready_to_arm()
14114
14115
# now test the total anglular difference:
14116
self.context_push()
14117
self.set_parameters({
14118
"COMPASS_OFS2_X": 1000,
14119
"COMPASS_OFS2_Y": -1000,
14120
"COMPASS_OFS2_Z": -10000,
14121
})
14122
self.assert_prearm_failure("Compasses inconsistent")
14123
self.context_pop()
14124
self.wait_ready_to_arm()
14125
# the following line papers over a probably problem with the
14126
# EKF recovering from bad compass offsets. Without it, the
14127
# EKF will maintain a 10-degree offset from the true compass
14128
# heading seemingly indefinitely.
14129
self.reboot_sitl()
14130
14131
def run_replay(self, filepath):
14132
'''runs replay in filepath, returns filepath to Replay logfile'''
14133
util.run_cmd(
14134
['build/sitl/tool/Replay', filepath],
14135
directory=util.topdir(),
14136
checkfail=True,
14137
show=True,
14138
output=True,
14139
)
14140
return self.current_onboard_log_filepath()
14141
14142
def AHRS_ORIENTATION(self):
14143
'''test AHRS_ORIENTATION parameter works'''
14144
self.context_push()
14145
self.wait_ready_to_arm()
14146
original_imu = self.assert_receive_message("RAW_IMU", verbose=True)
14147
self.set_parameter("AHRS_ORIENTATION", 16) # roll-90
14148
self.delay_sim_time(2) # we update this on a timer
14149
new_imu = self.assert_receive_message("RAW_IMU", verbose=True)
14150
delta_zacc = original_imu.zacc - new_imu.zacc
14151
delta_z_g = delta_zacc/1000.0 # milligravities -> gravities
14152
if delta_z_g - 1 > 0.1: # milligravities....
14153
raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_z_g=%f)" % (delta_z_g,))
14154
delta_yacc = original_imu.yacc - new_imu.yacc
14155
delta_y_g = delta_yacc/1000.0 # milligravities -> gravities
14156
if delta_y_g + 1 > 0.1:
14157
raise NotAchievedException("Magic AHRS_ORIENTATION update did not work (delta_y_g=%f)" % (delta_y_g,))
14158
self.context_pop()
14159
self.reboot_sitl()
14160
self.delay_sim_time(2) # we update orientation on a timer
14161
14162
def GPSTypes(self):
14163
'''check each simulated GPS works'''
14164
self.reboot_sitl()
14165
orig = self.poll_home_position(timeout=60)
14166
sim_gps = [
14167
# (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix)
14168
# if gps_type is None we auto-detect
14169
# (0, "NONE"),
14170
(1, "UBLOX", None, "u-blox", 5, 'probing'),
14171
(5, "NMEA", 5, "NMEA", 5, 'probing'),
14172
(6, "SBP", None, "SBP", 5, 'probing'),
14173
(8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS
14174
(9, "SBP2", None, "SBP2", 5, 'probing'),
14175
(10, "SBF", 10, 'SBF', 5, 'probing'),
14176
(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS
14177
(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS
14178
# (9, "FILE"),
14179
]
14180
self.context_collect("STATUSTEXT")
14181
for (sim_gps_type, name, gps_type, detect_name, serial_protocol, detect_prefix) in sim_gps:
14182
self.start_subtest("Checking GPS type %s" % name)
14183
self.set_parameter("SIM_GPS1_TYPE", sim_gps_type)
14184
self.set_parameter("SERIAL3_PROTOCOL", serial_protocol)
14185
if gps_type is None:
14186
gps_type = 1 # auto-detect
14187
self.set_parameter("GPS1_TYPE", gps_type)
14188
self.context_clear_collection('STATUSTEXT')
14189
self.reboot_sitl()
14190
if detect_prefix == "probing":
14191
self.wait_statustext(f"probing for {detect_name}", check_context=True)
14192
else:
14193
self.wait_statustext(f"specified as {detect_name}", check_context=True)
14194
self.wait_statustext(f"detected {detect_name}", check_context=True)
14195
n = self.poll_home_position(timeout=120)
14196
distance = self.get_distance_int(orig, n)
14197
if distance > 1:
14198
raise NotAchievedException(f"gps type {name} misbehaving")
14199
14200
def assert_gps_satellite_count(self, messagename, count):
14201
m = self.assert_receive_message(messagename)
14202
if m.satellites_visible != count:
14203
raise NotAchievedException("Expected %u sats, got %u" %
14204
(count, m.satellites_visible))
14205
14206
def check_attitudes_match(self):
14207
'''make sure ahrs2 and simstate and ATTTIUDE_QUATERNION all match'''
14208
14209
# these are ordered to bookend the list with timestamps (which
14210
# both attitude messages have):
14211
get_names = ['ATTITUDE', 'SIMSTATE', 'AHRS2', 'ATTITUDE_QUATERNION']
14212
msgs = self.get_messages_frame(get_names)
14213
14214
for get_name in get_names:
14215
self.progress("%s: %s" % (get_name, msgs[get_name]))
14216
14217
simstate = msgs['SIMSTATE']
14218
attitude = msgs['ATTITUDE']
14219
ahrs2 = msgs['AHRS2']
14220
attitude_quaternion = msgs['ATTITUDE_QUATERNION']
14221
14222
# check ATTITUDE
14223
want = math.degrees(simstate.roll)
14224
got = math.degrees(attitude.roll)
14225
if abs(mavextra.angle_diff(want, got)) > 20:
14226
raise NotAchievedException("ATTITUDE.Roll looks bad (want=%f got=%f)" %
14227
(want, got))
14228
want = math.degrees(simstate.pitch)
14229
got = math.degrees(attitude.pitch)
14230
if abs(mavextra.angle_diff(want, got)) > 20:
14231
raise NotAchievedException("ATTITUDE.Pitch looks bad (want=%f got=%f)" %
14232
(want, got))
14233
14234
# check AHRS2
14235
want = math.degrees(simstate.roll)
14236
got = math.degrees(ahrs2.roll)
14237
if abs(mavextra.angle_diff(want, got)) > 20:
14238
raise NotAchievedException("AHRS2.Roll looks bad (want=%f got=%f)" %
14239
(want, got))
14240
14241
want = math.degrees(simstate.pitch)
14242
got = math.degrees(ahrs2.pitch)
14243
if abs(mavextra.angle_diff(want, got)) > 20:
14244
raise NotAchievedException("AHRS2.Pitch looks bad (want=%f got=%f)" %
14245
(want, got))
14246
14247
# check ATTITUDE_QUATERNION
14248
q = quaternion.Quaternion([
14249
attitude_quaternion.q1,
14250
attitude_quaternion.q2,
14251
attitude_quaternion.q3,
14252
attitude_quaternion.q4
14253
])
14254
euler = q.euler
14255
self.progress("attquat:%s q:%s euler:%s" % (
14256
str(attitude_quaternion), q, euler))
14257
14258
want = math.degrees(simstate.roll)
14259
got = math.degrees(euler[0])
14260
if mavextra.angle_diff(want, got) > 20:
14261
raise NotAchievedException("quat roll differs from attitude roll; want=%f got=%f" %
14262
(want, got))
14263
14264
want = math.degrees(simstate.pitch)
14265
got = math.degrees(euler[1])
14266
if mavextra.angle_diff(want, got) > 20:
14267
raise NotAchievedException("quat pitch differs from attitude pitch; want=%f got=%f" %
14268
(want, got))
14269
14270
def MultipleGPS(self):
14271
'''check ArduPilot behaviour across multiple GPS units'''
14272
self.assert_message_rate_hz('GPS2_RAW', 0)
14273
14274
# we start sending GPS2_TYPE - but it will never actually be
14275
# filled in as _port[1] is only filled in in AP_GPS::init()
14276
self.start_subtest("Get GPS2_RAW as soon as we're configured for a second GPS")
14277
self.set_parameter("GPS2_TYPE", 1)
14278
self.assert_message_rate_hz('GPS2_RAW', 5)
14279
14280
self.start_subtest("Ensure correct fix type when no connected GPS")
14281
m = self.assert_receive_message("GPS2_RAW")
14282
self.progress(self.dump_message_verbose(m))
14283
if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_NO_GPS:
14284
raise NotAchievedException("Incorrect fix type")
14285
14286
self.start_subtest("Ensure detection when sim gps connected")
14287
self.set_parameter("SIM_GPS2_TYPE", 1)
14288
self.set_parameter("SIM_GPS2_ENABLE", 1)
14289
# a reboot is required after setting GPS2_TYPE. We start
14290
# sending GPS2_RAW out, once the parameter is set, but a
14291
# reboot is required because _port[1] is only set in
14292
# AP_GPS::init() at boot time, so it will never be detected.
14293
self.context_collect("STATUSTEXT")
14294
self.reboot_sitl()
14295
self.wait_statustext("GPS 1: detected u-blox", check_context=True)
14296
self.wait_statustext("GPS 2: detected u-blox", check_context=True)
14297
m = self.assert_receive_message("GPS2_RAW")
14298
self.progress(self.dump_message_verbose(m))
14299
# would be nice for it to take some time to get a fix....
14300
if m.fix_type != mavutil.mavlink.GPS_FIX_TYPE_RTK_FIXED:
14301
raise NotAchievedException("Incorrect fix type")
14302
14303
self.start_subtest("Check parameters are per-GPS")
14304
self.assert_parameter_value("SIM_GPS1_NUMSATS", 10)
14305
self.assert_gps_satellite_count("GPS_RAW_INT", 10)
14306
self.set_parameter("SIM_GPS1_NUMSATS", 13)
14307
self.assert_gps_satellite_count("GPS_RAW_INT", 13)
14308
14309
self.assert_parameter_value("SIM_GPS2_NUMSATS", 10)
14310
self.assert_gps_satellite_count("GPS2_RAW", 10)
14311
self.set_parameter("SIM_GPS2_NUMSATS", 12)
14312
self.assert_gps_satellite_count("GPS2_RAW", 12)
14313
14314
self.start_subtest("check that GLOBAL_POSITION_INT fails over")
14315
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14316
gpi_alt = m.alt
14317
for msg in ["GPS_RAW_INT", "GPS2_RAW"]:
14318
m = self.assert_receive_message(msg)
14319
if abs(m.alt - gpi_alt) > 100: # these are in mm
14320
raise NotAchievedException("Alt (%s) discrepancy; %d vs %d" %
14321
(msg, m.alt, gpi_alt))
14322
introduced_error = 10 # in metres
14323
self.set_parameter("SIM_GPS2_ALT_OFS", introduced_error)
14324
self.do_timesync_roundtrip()
14325
m = self.assert_receive_message("GPS2_RAW")
14326
if abs((m.alt-introduced_error*1000) - gpi_alt) > 100:
14327
raise NotAchievedException("skewed Alt (%s) discrepancy; %d+%d vs %d" %
14328
(msg, introduced_error*1000, m.alt, gpi_alt))
14329
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14330
new_gpi_alt = m.alt
14331
if abs(gpi_alt - new_gpi_alt) > 100:
14332
raise NotAchievedException("alt moved unexpectedly")
14333
self.progress("Killing first GPS")
14334
self.set_parameter("SIM_GPS1_ENABLE", 0)
14335
self.delay_sim_time(1)
14336
self.progress("Checking altitude now matches second GPS")
14337
m = self.assert_receive_message("GLOBAL_POSITION_INT")
14338
new_gpi_alt2 = m.alt
14339
m = self.assert_receive_message("GPS2_RAW")
14340
if abs(new_gpi_alt2 - m.alt) > 100:
14341
raise NotAchievedException("Failover not detected")
14342
14343
def fetch_file_via_ftp(self, path, timeout=20):
14344
'''returns the content of the FTP'able file at path'''
14345
self.progress("Retrieving (%s) using MAVProxy" % path)
14346
mavproxy = self.start_mavproxy()
14347
mavproxy.expect("Saved .* parameters to")
14348
ex = None
14349
tmpfile = tempfile.NamedTemporaryFile(mode='r', delete=False)
14350
try:
14351
mavproxy.send("module load ftp\n")
14352
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
14353
mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message
14354
mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))
14355
mavproxy.expect("Getting")
14356
tstart = self.get_sim_time()
14357
while True:
14358
now = self.get_sim_time()
14359
if now - tstart > timeout:
14360
raise NotAchievedException("expected complete transfer")
14361
self.progress("Polling status")
14362
mavproxy.send("ftp status\n")
14363
try:
14364
mavproxy.expect("No transfer in progress", timeout=1)
14365
break
14366
except Exception:
14367
continue
14368
# terminate the connection, or it may still be in progress the next time an FTP is attempted:
14369
mavproxy.send("ftp cancel\n")
14370
mavproxy.expect("Terminated session")
14371
except Exception as e:
14372
self.print_exception_caught(e)
14373
ex = e
14374
14375
self.stop_mavproxy(mavproxy)
14376
14377
if ex is not None:
14378
raise ex
14379
14380
return tmpfile.read()
14381
14382
def MAVFTP(self):
14383
'''ensure MAVProxy can do MAVFTP to ardupilot'''
14384
mavproxy = self.start_mavproxy()
14385
ex = None
14386
try:
14387
mavproxy.send("module load ftp\n")
14388
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
14389
mavproxy.send("ftp list\n")
14390
some_directory = None
14391
for entry in sorted(os.listdir(".")):
14392
if os.path.isdir(entry):
14393
some_directory = entry
14394
break
14395
if some_directory is None:
14396
raise NotAchievedException("No directories?!")
14397
expected_line = " D %s" % some_directory
14398
mavproxy.expect(expected_line) # one line from the ftp list output
14399
except Exception as e:
14400
self.print_exception_caught(e)
14401
ex = e
14402
14403
self.stop_mavproxy(mavproxy)
14404
14405
if ex is not None:
14406
raise ex
14407
14408
def write_content_to_filepath(self, content, filepath):
14409
'''write biunary content to filepath'''
14410
with open(filepath, "wb") as f:
14411
if sys.version_info.major >= 3:
14412
if not isinstance(content, bytes):
14413
raise NotAchievedException("Want bytes to write_content_to_filepath")
14414
f.write(content)
14415
f.close()
14416
14417
def add_embedded_params_to_binary(self, binary, defaults):
14418
sys.path.insert(1, os.path.join(self.rootdir(), 'Tools', 'scripts'))
14419
import apj_tool
14420
14421
# copy binary
14422
if getattr(self, "embedded_default_counter", None) is None:
14423
self.embedded_default_counter = 0
14424
self.embedded_default_counter += 1
14425
14426
new_filepath = binary + "-newdefaults-%u" % self.embedded_default_counter
14427
shutil.copy(binary, new_filepath)
14428
14429
# create file for defaults
14430
defaults_filepath = "embed-these-defaults.txt"
14431
self.write_content_to_filepath(defaults.encode('utf-8'), defaults_filepath)
14432
14433
# do the needful
14434
a = apj_tool.embedded_defaults(new_filepath)
14435
if not a.find():
14436
raise NotAchievedException("Did not find defaults")
14437
a.set_file(defaults_filepath)
14438
a.save()
14439
14440
return new_filepath
14441
14442
def sample_param_file_content(self):
14443
'''returns an array of tuples, (param file content, dictionary of what
14444
parameter values should be tested afterwards)'''
14445
dashes = "-" * 150
14446
return [
14447
# multiple lines:
14448
("""SERIAL5_BAUD 1234
14449
SERIAL4_BAUD=4567
14450
""", {"SERIAL5_BAUD": 1234, "SERIAL4_BAUD": 4567}),
14451
14452
# line missing CR:
14453
("""SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 6789}),
14454
14455
# commented-out line:
14456
("""# SERIAL5_BAUD 6789""", {"SERIAL5_BAUD": 57}),
14457
14458
# very long comment line followed by more text:
14459
("""SERIAL4_BAUD 6789
14460
# awesome dashes: %s
14461
SERIAL5_BAUD 128
14462
""" % dashes, {"SERIAL4_BAUD": 6789, "SERIAL5_BAUD": 128}),
14463
14464
]
14465
14466
def EmbeddedParamParser(self):
14467
'''check parsing of embedded defaults file'''
14468
# warning: don't try this test on Copter as it won't boot
14469
# without the passed-in file (which we don't parse if there
14470
# are embedded defaults)
14471
for (content, param_values) in self.sample_param_file_content():
14472
binary_with_defaults = self.add_embedded_params_to_binary(self.binary, content)
14473
self.customise_SITL_commandline([], binary=binary_with_defaults)
14474
self.assert_parameter_values(param_values)
14475
14476
def _MotorTest(self,
14477
command,
14478
timeout=60,
14479
mot1_servo_chan=1,
14480
mot4_servo_chan=4,
14481
wait_finish_text=True,
14482
quadplane=False):
14483
'''Run Motor Tests (with specific mavlink message)'''
14484
self.start_subtest("Testing PWM output")
14485
pwm_in = 1300
14486
# default frame is "+" - start motor of 2 is "B", which is
14487
# motor 1... see
14488
# https://ardupilot.org/copter/docs/connect-escs-and-motors.html
14489
command(
14490
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
14491
p1=2, # start motor
14492
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
14493
p3=pwm_in, # pwm-to-output
14494
p4=2, # timeout in seconds
14495
p5=2, # number of motors to output
14496
p6=0, # compass learning
14497
timeout=timeout,
14498
)
14499
# long timeouts here because there's a pause before we start motors
14500
self.wait_servo_channel_value(mot1_servo_chan, pwm_in, timeout=10)
14501
self.wait_servo_channel_value(mot4_servo_chan, pwm_in, timeout=10)
14502
if wait_finish_text:
14503
self.wait_statustext("finished motor test")
14504
self.wait_disarmed()
14505
# wait_disarmed is not sufficient here; it's actually the
14506
# *motors* being armed which causes the problem, not the
14507
# vehicle's arm state! Could we use SYS_STATUS here instead?
14508
self.delay_sim_time(10)
14509
self.end_subtest("Testing PWM output")
14510
14511
self.start_subtest("Testing percentage output")
14512
percentage = 90.1
14513
# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3
14514
# min/max are used.
14515
expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0
14516
# quadplane doesn't use the expect value - it wants 1900
14517
# rather than the calculated 1901...
14518
if quadplane:
14519
expected_pwm = 1900
14520
self.progress("expected pwm=%f" % expected_pwm)
14521
command(
14522
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
14523
p1=2, # start motor
14524
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,
14525
p3=percentage, # pwm-to-output
14526
p4=2, # timeout in seconds
14527
p5=2, # number of motors to output
14528
p6=0, # compass learning
14529
timeout=timeout,
14530
)
14531
self.wait_servo_channel_value(mot1_servo_chan, expected_pwm, timeout=10)
14532
self.wait_servo_channel_value(mot4_servo_chan, expected_pwm, timeout=10)
14533
if wait_finish_text:
14534
self.wait_statustext("finished motor test")
14535
self.wait_disarmed()
14536
# wait_disarmed is not sufficient here; it's actually the
14537
# *motors* being armed which causes the problem, not the
14538
# vehicle's arm state! Could we use SYS_STATUS here instead?
14539
self.delay_sim_time(10)
14540
self.end_subtest("Testing percentage output")
14541
14542
def MotorTest(self, timeout=60, **kwargs):
14543
'''Run Motor Tests''' # common to Copter and QuadPlane
14544
self._MotorTest(self.run_cmd, **kwargs)
14545
self._MotorTest(self.run_cmd_int, **kwargs)
14546
14547
def test_ibus_voltage(self, message):
14548
batt = self.mav.recv_match(
14549
type='BATTERY_STATUS',
14550
blocking=True,
14551
timeout=5,
14552
condition="BATTERY_STATUS.id==0"
14553
)
14554
if batt is None:
14555
raise NotAchievedException("Did not get BATTERY_STATUS message")
14556
want = int(batt.voltages[0] * 0.1)
14557
14558
if want != message.get_sensor_value():
14559
raise NotAchievedException("Bad voltage (want=%u got=%u)" %
14560
(want, message.get_sensor_value()))
14561
self.progress("iBus voltage OK")
14562
14563
def test_ibus_armed(self, message):
14564
got = message.get_sensor_value()
14565
want = 1 if self.armed() else 0
14566
if got != want:
14567
raise NotAchievedException("Expected armed %u got %u" %
14568
(want, got))
14569
self.progress("iBus armed OK")
14570
14571
def test_ibus_mode(self, message):
14572
got = message.get_sensor_value()
14573
want = self.mav.messages['HEARTBEAT'].custom_mode
14574
if got != want:
14575
raise NotAchievedException("Expected mode %u got %u" %
14576
(want, got))
14577
self.progress("iBus mode OK")
14578
14579
def test_ibus_get_response(self, ibus, timeout=5):
14580
tstart = self.get_sim_time()
14581
while True:
14582
now = self.get_sim_time()
14583
if now - tstart > timeout:
14584
raise AutoTestTimeoutException("Failed to get ibus data")
14585
packet = ibus.update()
14586
if packet is not None:
14587
return packet
14588
14589
def IBus(self):
14590
'''test the IBus protocol'''
14591
self.set_parameter("SERIAL5_PROTOCOL", 49)
14592
self.customise_SITL_commandline([
14593
"--serial5=tcp:6735" # serial5 spews to localhost:6735
14594
])
14595
ibus = IBus(("127.0.0.1", 6735))
14596
ibus.connect()
14597
14598
# expected_sensors should match the list created in AP_IBus_Telem
14599
expected_sensors = {
14600
# sensor id : (len, IBUS_MEAS_TYPE_*, test_function)
14601
1: (2, 0x15, self.test_ibus_armed),
14602
2: (2, 0x16, self.test_ibus_mode),
14603
5: (2, 0x03, self.test_ibus_voltage),
14604
}
14605
14606
for (sensor_addr, results) in expected_sensors.items():
14607
# first make sure it is present:
14608
request = IBusRequest_DISCOVER(sensor_addr)
14609
ibus.port.sendall(request.for_wire())
14610
14611
packet = self.test_ibus_get_response(ibus)
14612
if packet.address != sensor_addr:
14613
raise ValueError("Unexpected sensor address %u" %
14614
(packet.address,))
14615
14616
(expected_length, expected_type, validator) = results
14617
14618
self.progress("Getting sensor (%x) type" % (sensor_addr))
14619
request = IBusRequest_GET_SENSOR_TYPE(sensor_addr)
14620
ibus.port.sendall(request.for_wire())
14621
14622
packet = self.test_ibus_get_response(ibus)
14623
if packet.address != sensor_addr:
14624
raise ValueError("Unexpected sensor address %u" %
14625
(packet.address,))
14626
14627
if packet.sensor_type != expected_type:
14628
raise ValueError("Unexpected sensor type want=%u got=%u" %
14629
(expected_type, packet.sensor_type))
14630
14631
if packet.sensor_length != expected_length:
14632
raise ValueError("Unexpected sensor len want=%u got=%u" %
14633
(expected_length, packet.sensor_length))
14634
14635
self.progress("Getting sensor (%x) value" % (sensor_addr))
14636
request = IBusRequest_GET_SENSOR_VALUE(sensor_addr)
14637
ibus.port.sendall(request.for_wire())
14638
14639
packet = self.test_ibus_get_response(ibus)
14640
validator(packet)
14641
14642
# self.progress("Ensure we cover all sensors")
14643
# for i in range(1, 17): # zero is special
14644
# if i in expected_sensors:
14645
# continue
14646
# request = IBusRequest_DISCOVER(i)
14647
# ibus.port.sendall(request.for_wire())
14648
14649
# try:
14650
# packet = self.test_ibus_get_response(ibus, timeout=1)
14651
# except AutoTestTimeoutException:
14652
# continue
14653
# self.progress("Received packet (%s)" % str(packet))
14654
# raise NotAchievedException("IBus sensor %u is untested" % i)
14655
14656
def tests(self):
14657
return [
14658
self.PIDTuning,
14659
self.ArmFeatures,
14660
self.SetHome,
14661
self.ConfigErrorLoop,
14662
self.CPUFailsafe,
14663
self.Parameters,
14664
self.LoggerDocumentation,
14665
self.Logging,
14666
self.GetCapabilities,
14667
self.InitialMode,
14668
]
14669
14670
def post_tests_announcements(self):
14671
if self._show_test_timings:
14672
if self.waiting_to_arm_count == 0:
14673
avg = None
14674
else:
14675
avg = self.total_waiting_to_arm_time/self.waiting_to_arm_count
14676
self.progress("Spent %f seconds waiting to arm. count=%u avg=%s" %
14677
(self.total_waiting_to_arm_time,
14678
self.waiting_to_arm_count,
14679
str(avg)))
14680
self.show_test_timings()
14681
if self.forced_post_test_sitl_reboots != 0:
14682
print("Had to force-reset SITL %u times" %
14683
(self.forced_post_test_sitl_reboots,))
14684
14685
def autotest(self, tests=None, allow_skips=True, step_name=None):
14686
"""Autotest used by ArduPilot autotest CI."""
14687
if tests is None:
14688
tests = self.tests()
14689
all_tests = []
14690
for test in tests:
14691
if not isinstance(test, Test):
14692
test = Test(test)
14693
all_tests.append(test)
14694
14695
disabled = self.disabled_tests()
14696
if not allow_skips:
14697
disabled = {}
14698
skip_list = []
14699
tests = []
14700
seen_test_name = set()
14701
for test in all_tests:
14702
if test.name in seen_test_name:
14703
raise ValueError("Duplicate test name %s" % test.name)
14704
seen_test_name.add(test.name)
14705
if test.name in disabled:
14706
self.progress("##### %s is skipped: %s" % (test, disabled[test.name]))
14707
skip_list.append((test, disabled[test.name]))
14708
continue
14709
tests.append(test)
14710
14711
results = self.run_tests(tests)
14712
14713
if len(skip_list):
14714
self.progress("Skipped tests:")
14715
for skipped in skip_list:
14716
(test, reason) = skipped
14717
print(" %s (see %s)" % (test.name, reason))
14718
14719
self.fail_list = list(filter(lambda x : not x.passed, results))
14720
if len(self.fail_list):
14721
self.progress("Failing tests:")
14722
for failure in self.fail_list:
14723
print(str(failure))
14724
14725
self.post_tests_announcements()
14726
if self.generate_junit:
14727
if step_name is None:
14728
step_name = "Unknown_step_name"
14729
step_name.replace(".", "_")
14730
self.create_junit_report(step_name, results, skip_list)
14731
14732
return len(self.fail_list) == 0
14733
14734
def create_junit_report(self, test_name: str, results: List[Result], skip_list: List[Tuple[Test, Dict[str, str]]]) -> None:
14735
"""Generate Junit report from the autotest results"""
14736
from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure
14737
frame = self.vehicleinfo_key()
14738
xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml"
14739
self.progress(f"Writing test result in jUnit format to {xml_filename}\n")
14740
14741
suite = TestSuite(f"Autotest {frame} {test_name}")
14742
suite.timestamp = datetime.now().replace(microsecond=0).isoformat()
14743
for result in results:
14744
case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed)
14745
# f"{result.test.description}"
14746
# case.file ## TODO : add file properties to match test location
14747
if not result.passed:
14748
case.result = [Failure(f"see {result.debug_filename}", f"{result.exception}")]
14749
suite.add_testcase(case)
14750
for skipped in skip_list:
14751
(test, reason) = skipped
14752
case = TestCase(f"{test.name}", f"{test.function}")
14753
case.result = [Skipped(f"Skipped : {reason}")]
14754
14755
suite.add_property("Firmware Version Major", self.fcu_firmware_version[0])
14756
suite.add_property("Firmware Version Minor", self.fcu_firmware_version[1])
14757
suite.add_property("Firmware Version Rev", self.fcu_firmware_version[2])
14758
suite.add_property("Firmware hash", self.fcu_firmware_hash)
14759
suite.add_property("Git hash", self.githash)
14760
mavproxy_version = util.MAVProxy_version()
14761
suite.add_property("Mavproxy Version Major", mavproxy_version[0])
14762
suite.add_property("Mavproxy Version Minor", mavproxy_version[1])
14763
suite.add_property("Mavproxy Version Rev", mavproxy_version[2])
14764
14765
xml = JUnitXml()
14766
xml.add_testsuite(suite)
14767
xml.write(xml_filename, pretty=True)
14768
14769
def mavfft_fttd(self, sensor_type, sensor_instance, since, until):
14770
'''display fft for raw ACC data in current logfile'''
14771
14772
'''object to store data about a single FFT plot'''
14773
class MessageData(object):
14774
def __init__(self, ffth):
14775
self.seqno = -1
14776
self.fftnum = ffth.N
14777
self.sensor_type = ffth.type
14778
self.instance = ffth.instance
14779
self.sample_rate_hz = ffth.smp_rate
14780
self.multiplier = ffth.mul
14781
self.sample_us = ffth.SampleUS
14782
self.data = {}
14783
self.data["X"] = []
14784
self.data["Y"] = []
14785
self.data["Z"] = []
14786
self.holes = False
14787
self.freq = None
14788
14789
def add_fftd(self, fftd):
14790
self.seqno += 1
14791
self.data["X"].extend(fftd.x)
14792
self.data["Y"].extend(fftd.y)
14793
self.data["Z"].extend(fftd.z)
14794
14795
mlog = self.dfreader_for_current_onboard_log()
14796
14797
# see https://holometer.fnal.gov/GH_FFT.pdf for a description of the techniques used here
14798
messages = []
14799
messagedata = None
14800
while True:
14801
m = mlog.recv_match()
14802
if m is None:
14803
break
14804
msg_type = m.get_type()
14805
if msg_type == "ISBH":
14806
if messagedata is not None:
14807
if (messagedata.sensor_type == sensor_type and
14808
messagedata.instance == sensor_instance and
14809
messagedata.sample_us > since and
14810
messagedata.sample_us < until):
14811
messages.append(messagedata)
14812
messagedata = MessageData(m)
14813
continue
14814
14815
if msg_type == "ISBD":
14816
if (messagedata is not None and
14817
messagedata.sensor_type == sensor_type and
14818
messagedata.instance == sensor_instance):
14819
messagedata.add_fftd(m)
14820
14821
fft_len = len(messages[0].data["X"])
14822
sum_fft = {
14823
"X": numpy.zeros(int(fft_len / 2 + 1)),
14824
"Y": numpy.zeros(int(fft_len / 2 + 1)),
14825
"Z": numpy.zeros(int(fft_len / 2 + 1)),
14826
}
14827
sample_rate = 0
14828
counts = 0
14829
window = numpy.hanning(fft_len)
14830
# The returned float array f contains the frequency bin centers in cycles per unit of the
14831
# sample spacing (with zero at the start).
14832
freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz)
14833
14834
# calculate NEBW constant
14835
S2 = numpy.inner(window, window)
14836
14837
for message in messages:
14838
for axis in ["X", "Y", "Z"]:
14839
# normalize data and convert to dps in order to produce more meaningful magnitudes
14840
if message.sensor_type == 1:
14841
d = numpy.array(numpy.degrees(message.data[axis])) / float(message.multiplier)
14842
else:
14843
d = numpy.array(message.data[axis]) / float(message.multiplier)
14844
14845
# apply window to the input
14846
d *= window
14847
# perform RFFT
14848
d_fft = numpy.fft.rfft(d)
14849
# convert to squared complex magnitude
14850
d_fft = numpy.square(abs(d_fft))
14851
# remove DC component
14852
d_fft[0] = 0
14853
d_fft[-1] = 0
14854
# accumulate the sums
14855
sum_fft[axis] += d_fft
14856
14857
sample_rate = message.sample_rate_hz
14858
counts += 1
14859
14860
numpy.seterr(divide='ignore')
14861
psd = {}
14862
for axis in ["X", "Y", "Z"]:
14863
# normalize output to averaged PSD
14864
psd[axis] = 2 * (sum_fft[axis] / counts) / (sample_rate * S2)
14865
psd[axis] = 10 * numpy.log10(psd[axis])
14866
14867
psd["F"] = freqmap
14868
14869
return psd
14870
14871
def model_defaults_filepath(self, model):
14872
vehicle = self.vehicleinfo_key()
14873
vinfo = vehicleinfo.VehicleInfo()
14874
defaults_filepath = vinfo.options[vehicle]["frames"][model]["default_params_filename"]
14875
if isinstance(defaults_filepath, str):
14876
defaults_filepath = [defaults_filepath]
14877
defaults_list = []
14878
for d in defaults_filepath:
14879
defaults_list.append(util.reltopdir(os.path.join(testdir, d)))
14880
return defaults_list
14881
14882
def load_default_params_file(self, filename):
14883
'''load a file from Tools/autotest/default_params'''
14884
filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename))
14885
self.repeatedly_apply_parameter_filepath(filepath)
14886
14887
def load_params_file(self, filename):
14888
'''load a file from test-specific directory'''
14889
filepath = os.path.join(testdir, self.current_test_name_directory, filename)
14890
self.repeatedly_apply_parameter_filepath(filepath)
14891
14892
def send_pause_command(self):
14893
'''pause AUTO/GUIDED modes'''
14894
self.run_cmd(
14895
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
14896
p1=0, # 0: pause, 1: continue
14897
)
14898
14899
def send_resume_command(self):
14900
'''resume AUTO/GUIDED modes'''
14901
self.run_cmd(
14902
mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE,
14903
p1=1, # 0: pause, 1: continue
14904
)
14905
14906
def enum_state_name(self, enum_name, state, pretrim=None):
14907
e = mavutil.mavlink.enums[enum_name]
14908
e_value = e[state]
14909
name = e_value.name
14910
if pretrim is not None:
14911
if not pretrim.startswith(pretrim):
14912
raise NotAchievedException("Expected %s to pretrim" % (pretrim))
14913
name = name.replace(pretrim, "")
14914
return name
14915
14916
def vtol_state_name(self, state):
14917
return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_")
14918
14919
def landed_state_name(self, state):
14920
return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_")
14921
14922
def assert_extended_sys_state(self, vtol_state, landed_state):
14923
m = self.assert_receive_message('EXTENDED_SYS_STATE', timeout=1)
14924
if m.vtol_state != vtol_state:
14925
raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" %
14926
(self.vtol_state_name(vtol_state),
14927
self.vtol_state_name(m.vtol_state)))
14928
if m.landed_state != landed_state:
14929
raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" %
14930
(self.landed_state_name(landed_state),
14931
self.landed_state_name(m.landed_state)))
14932
14933
def wait_extended_sys_state(self, vtol_state, landed_state, timeout=10):
14934
tstart = self.get_sim_time()
14935
while True:
14936
if self.get_sim_time() - tstart > timeout:
14937
raise NotAchievedException("Did not achieve vol/landed states")
14938
self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" %
14939
(self.vtol_state_name(vtol_state),
14940
self.landed_state_name(landed_state)))
14941
m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True)
14942
if m.landed_state != landed_state:
14943
self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" %
14944
(self.landed_state_name(landed_state),
14945
self.landed_state_name(m.landed_state)))
14946
continue
14947
if m.vtol_state != vtol_state:
14948
self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" %
14949
(self.vtol_state_name(vtol_state),
14950
self.vtol_state_name(m.vtol_state)))
14951
continue
14952
14953
self.progress("vtol and landed states match")
14954
return
14955
14956
def setGCSfailsafe(self, paramValue):
14957
# Slow down the sim rate if GCS Failsafe is in use
14958
if paramValue == 0:
14959
self.set_parameters({
14960
"FS_GCS_ENABLE": paramValue,
14961
"SIM_SPEEDUP": 10,
14962
})
14963
else:
14964
self.set_parameters({
14965
"SIM_SPEEDUP": 4,
14966
"FS_GCS_ENABLE": paramValue,
14967
})
14968
14969