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/rover.py
Views: 1798
1
'''
2
Drive Rover in SITL
3
4
AP_FLAKE8_CLEAN
5
6
'''
7
8
from __future__ import print_function
9
10
import copy
11
import math
12
import operator
13
import os
14
import sys
15
import time
16
17
import vehicle_test_suite
18
19
from pysim import util
20
21
from vehicle_test_suite import AutoTestTimeoutException
22
from vehicle_test_suite import NotAchievedException
23
from vehicle_test_suite import PreconditionFailedException
24
25
from pymavlink import mavextra
26
from pymavlink import mavutil
27
28
# get location of scripts
29
testdir = os.path.dirname(os.path.realpath(__file__))
30
31
SITL_START_LOCATION = mavutil.location(40.071374969556928,
32
-105.22978898137808,
33
1583.702759,
34
246)
35
36
37
class AutoTestRover(vehicle_test_suite.TestSuite):
38
@staticmethod
39
def get_not_armable_mode_list():
40
return ["RTL", "SMART_RTL"]
41
42
@staticmethod
43
def get_not_disarmed_settable_modes_list():
44
return ["FOLLOW"]
45
46
@staticmethod
47
def get_no_position_not_settable_modes_list():
48
return []
49
50
@staticmethod
51
def get_position_armable_modes_list():
52
return ["GUIDED", "LOITER", "STEERING", "AUTO"]
53
54
@staticmethod
55
def get_normal_armable_modes_list():
56
return ["ACRO", "HOLD", "MANUAL"]
57
58
def log_name(self):
59
return "Rover"
60
61
def test_filepath(self):
62
return os.path.realpath(__file__)
63
64
def set_current_test_name(self, name):
65
self.current_test_name_directory = "ArduRover_Tests/" + name + "/"
66
67
def sitl_start_location(self):
68
return SITL_START_LOCATION
69
70
def default_frame(self):
71
return "rover"
72
73
def default_speedup(self):
74
return 30
75
76
def is_rover(self):
77
return True
78
79
def get_stick_arming_channel(self):
80
return int(self.get_parameter("RCMAP_ROLL"))
81
82
##########################################################
83
# TESTS DRIVE
84
##########################################################
85
# Drive a square in manual mode
86
def DriveSquare(self, side=50):
87
"""Learn/Drive Square with Ch7 option"""
88
89
self.progress("TEST SQUARE")
90
self.set_parameters({
91
"RC7_OPTION": 7,
92
"RC9_OPTION": 58,
93
})
94
95
self.change_mode('MANUAL')
96
97
self.wait_ready_to_arm()
98
self.arm_vehicle()
99
100
self.clear_wp(9)
101
102
# first aim north
103
self.progress("\nTurn right towards north")
104
self.reach_heading_manual(10)
105
# save bottom left corner of box as home AND waypoint
106
self.progress("Save HOME")
107
self.save_wp()
108
109
self.progress("Save WP")
110
self.save_wp()
111
112
# pitch forward to fly north
113
self.progress("\nGoing north %u meters" % side)
114
self.reach_distance_manual(side)
115
# save top left corner of square as waypoint
116
self.progress("Save WP")
117
self.save_wp()
118
119
# roll right to fly east
120
self.progress("\nGoing east %u meters" % side)
121
self.reach_heading_manual(100)
122
self.reach_distance_manual(side)
123
# save top right corner of square as waypoint
124
self.progress("Save WP")
125
self.save_wp()
126
127
# pitch back to fly south
128
self.progress("\nGoing south %u meters" % side)
129
self.reach_heading_manual(190)
130
self.reach_distance_manual(side)
131
# save bottom right corner of square as waypoint
132
self.progress("Save WP")
133
self.save_wp()
134
135
# roll left to fly west
136
self.progress("\nGoing west %u meters" % side)
137
self.reach_heading_manual(280)
138
self.reach_distance_manual(side)
139
# save bottom left corner of square (should be near home) as waypoint
140
self.progress("Save WP")
141
self.save_wp()
142
143
self.progress("Checking number of saved waypoints")
144
mavproxy = self.start_mavproxy()
145
num_wp = self.save_mission_to_file_using_mavproxy(
146
mavproxy,
147
os.path.join(testdir, "ch7_mission.txt"))
148
self.stop_mavproxy(mavproxy)
149
expected = 7 # home + 6 toggled in
150
if num_wp != expected:
151
raise NotAchievedException("Did not get %u waypoints; got %u" %
152
(expected, num_wp))
153
154
# TODO: actually drive the mission
155
156
self.clear_wp(9)
157
158
self.disarm_vehicle()
159
160
def drive_left_circuit(self):
161
"""Drive a left circuit, 50m on a side."""
162
self.change_mode('MANUAL')
163
self.set_rc(3, 2000)
164
165
self.progress("Driving left circuit")
166
# do 4 turns
167
for i in range(0, 4):
168
# hard left
169
self.progress("Starting turn %u" % i)
170
self.set_rc(1, 1000)
171
self.wait_heading(270 - (90*i), accuracy=10)
172
self.set_rc(1, 1500)
173
self.progress("Starting leg %u" % i)
174
self.wait_distance(50, accuracy=7)
175
self.set_rc(3, 1500)
176
self.progress("Circuit complete")
177
178
# def test_throttle_failsafe(self, home, distance_min=10, side=60,
179
# timeout=300):
180
# """Fly east, Failsafe, return, land."""
181
#
182
# self.mavproxy.send('switch 6\n') # manual mode
183
# self.wait_mode('MANUAL')
184
# self.mavproxy.send("param set FS_ACTION 1\n")
185
#
186
# # first aim east
187
# self.progress("turn east")
188
# if not self.reach_heading_manual(135):
189
# return False
190
#
191
# # fly east 60 meters
192
# self.progress("# Going forward %u meters" % side)
193
# if not self.reach_distance_manual(side):
194
# return False
195
#
196
# # pull throttle low
197
# self.progress("# Enter Failsafe")
198
# self.mavproxy.send('rc 3 900\n')
199
#
200
# tstart = self.get_sim_time()
201
# success = False
202
# while self.get_sim_time() < tstart + timeout and not success:
203
# m = self.mav.recv_match(type='VFR_HUD', blocking=True)
204
# pos = self.mav.location()
205
# home_distance = self.get_distance(home, pos)
206
# self.progress("Alt: %u HomeDistance: %.0f" %
207
# (m.alt, home_distance))
208
# # check if we've reached home
209
# if home_distance <= distance_min:
210
# self.progress("RTL Complete")
211
# success = True
212
#
213
# # reduce throttle
214
# self.mavproxy.send('rc 3 1500\n')
215
# self.mavproxy.expect('AP: Failsafe ended')
216
# self.mavproxy.send('switch 2\n') # manual mode
217
# self.wait_heartbeat()
218
# self.wait_mode('MANUAL')
219
#
220
# if success:
221
# self.progress("Reached failsafe home OK")
222
# return True
223
# else:
224
# self.progress("Failed to reach Home on failsafe RTL - "
225
# "timed out after %u seconds" % timeout)
226
# return False
227
228
def Sprayer(self):
229
"""Test sprayer functionality."""
230
rc_ch = 5
231
pump_ch = 5
232
spinner_ch = 6
233
pump_ch_min = 1050
234
pump_ch_trim = 1520
235
pump_ch_max = 1950
236
spinner_ch_min = 975
237
spinner_ch_trim = 1510
238
spinner_ch_max = 1975
239
240
self.set_parameters({
241
"SPRAY_ENABLE": 1,
242
243
"SERVO%u_FUNCTION" % pump_ch: 22,
244
"SERVO%u_MIN" % pump_ch: pump_ch_min,
245
"SERVO%u_TRIM" % pump_ch: pump_ch_trim,
246
"SERVO%u_MAX" % pump_ch: pump_ch_max,
247
248
"SERVO%u_FUNCTION" % spinner_ch: 23,
249
"SERVO%u_MIN" % spinner_ch: spinner_ch_min,
250
"SERVO%u_TRIM" % spinner_ch: spinner_ch_trim,
251
"SERVO%u_MAX" % spinner_ch: spinner_ch_max,
252
253
"SIM_SPR_ENABLE": 1,
254
"SIM_SPR_PUMP": pump_ch,
255
"SIM_SPR_SPIN": spinner_ch,
256
257
"RC%u_OPTION" % rc_ch: 15,
258
"LOG_DISARMED": 1,
259
})
260
261
self.reboot_sitl()
262
263
self.wait_ready_to_arm()
264
self.arm_vehicle()
265
266
self.progress("test bootup state - it's zero-output!")
267
self.wait_servo_channel_value(spinner_ch, 0)
268
self.wait_servo_channel_value(pump_ch, 0)
269
270
self.progress("Enable sprayer")
271
self.set_rc(rc_ch, 2000)
272
273
self.progress("Testing zero-speed state")
274
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
275
self.wait_servo_channel_value(pump_ch, pump_ch_min)
276
277
self.progress("Testing turning it off")
278
self.set_rc(rc_ch, 1000)
279
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
280
self.wait_servo_channel_value(pump_ch, pump_ch_min)
281
282
self.progress("Testing turning it back on")
283
self.set_rc(rc_ch, 2000)
284
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
285
self.wait_servo_channel_value(pump_ch, pump_ch_min)
286
287
self.progress("Testing speed-ramping")
288
self.set_rc(3, 1700) # start driving forward
289
290
# this is somewhat empirical...
291
self.wait_servo_channel_value(pump_ch, 1695, timeout=60)
292
293
self.progress("Turning it off again")
294
self.set_rc(rc_ch, 1000)
295
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
296
self.wait_servo_channel_value(pump_ch, pump_ch_min)
297
298
self.start_subtest("Sprayer Mission")
299
self.load_mission("sprayer-mission.txt")
300
self.change_mode("AUTO")
301
# self.send_debug_trap()
302
self.progress("Waiting for sprayer to start")
303
self.wait_servo_channel_value(pump_ch, 1250, timeout=60, comparator=operator.gt)
304
self.progress("Waiting for sprayer to stop")
305
self.wait_servo_channel_value(pump_ch, pump_ch_min, timeout=120)
306
307
self.start_subtest("Checking mavlink commands")
308
self.change_mode("MANUAL")
309
self.progress("Starting Sprayer")
310
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1)
311
312
self.progress("Testing speed-ramping")
313
self.set_rc(3, 1700) # start driving forward
314
self.wait_servo_channel_value(pump_ch, 1690, timeout=60, comparator=operator.gt)
315
self.start_subtest("Stopping Sprayer")
316
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0)
317
self.wait_servo_channel_value(pump_ch, pump_ch_min)
318
self.set_rc(3, 1000) # stop driving forward
319
320
self.progress("Sprayer OK")
321
self.disarm_vehicle()
322
323
def DriveMaxRCIN(self, timeout=30):
324
"""Drive rover at max RC inputs"""
325
self.progress("Testing max RC inputs")
326
self.change_mode("MANUAL")
327
328
self.wait_ready_to_arm()
329
self.arm_vehicle()
330
331
self.set_rc(3, 2000)
332
self.set_rc(1, 1000)
333
334
tstart = self.get_sim_time()
335
while self.get_sim_time_cached() - tstart < timeout:
336
m = self.assert_receive_message('VFR_HUD')
337
self.progress("Current speed: %f" % m.groundspeed)
338
339
self.disarm_vehicle()
340
341
#################################################
342
# AUTOTEST ALL
343
#################################################
344
def drive_mission(self, filename, strict=True):
345
"""Drive a mission from a file."""
346
self.progress("Driving mission %s" % filename)
347
wp_count = self.load_mission(filename, strict=strict)
348
self.wait_ready_to_arm()
349
self.arm_vehicle()
350
self.change_mode('AUTO')
351
self.wait_waypoint(1, wp_count-1, max_dist=5)
352
self.wait_statustext("Mission Complete", timeout=600)
353
self.disarm_vehicle()
354
self.progress("Mission OK")
355
356
def DriveMission(self):
357
'''Drive Mission rover1.txt'''
358
self.drive_mission("rover1.txt", strict=False)
359
360
def GripperMission(self):
361
'''Test Gripper Mission Items'''
362
self.load_mission("rover-gripper-mission.txt")
363
self.change_mode('AUTO')
364
self.wait_ready_to_arm()
365
self.arm_vehicle()
366
self.context_collect('STATUSTEXT')
367
self.wait_statustext("Gripper Grabbed", timeout=60, check_context=True)
368
self.wait_statustext("Gripper Released", timeout=60, check_context=True)
369
self.wait_statustext("Mission Complete", timeout=60, check_context=True)
370
self.disarm_vehicle()
371
372
def _MAV_CMD_DO_SEND_BANNER(self, run_cmd):
373
'''Get Banner'''
374
self.context_push()
375
self.context_collect('STATUSTEXT')
376
run_cmd(mavutil.mavlink.MAV_CMD_DO_SEND_BANNER)
377
self.wait_statustext("ArduRover", timeout=1, check_context=True)
378
self.context_pop()
379
380
def MAV_CMD_DO_SEND_BANNER(self):
381
'''test MAV_CMD_DO_SEND_BANNER'''
382
self._MAV_CMD_DO_SEND_BANNER(self.run_cmd)
383
self._MAV_CMD_DO_SEND_BANNER(self.run_cmd_int)
384
385
def drive_brake_get_stopping_distance(self, speed):
386
'''measure our stopping distance'''
387
388
self.context_push()
389
390
# controller tends not to meet cruise speed (max of ~14 when 15
391
# set), thus *1.2
392
# at time of writing, the vehicle is only capable of 10m/s/s accel
393
self.set_parameters({
394
'CRUISE_SPEED': speed*1.2,
395
'ATC_ACCEL_MAX': 15,
396
})
397
self.change_mode("STEERING")
398
self.set_rc(3, 2000)
399
self.wait_groundspeed(15, 100)
400
initial = self.mav.location()
401
initial_time = time.time()
402
while time.time() - initial_time < 2:
403
# wait for a position update from the autopilot
404
start = self.mav.location()
405
if start != initial:
406
break
407
self.set_rc(3, 1500)
408
self.wait_groundspeed(0, 0.2) # why do we not stop?!
409
initial = self.mav.location()
410
initial_time = time.time()
411
while time.time() - initial_time < 2:
412
# wait for a position update from the autopilot
413
stop = self.mav.location()
414
if stop != initial:
415
break
416
delta = self.get_distance(start, stop)
417
418
self.context_pop()
419
420
return delta
421
422
def DriveBrake(self):
423
'''Test braking'''
424
self.set_parameters({
425
'CRUISE_SPEED': 15,
426
'ATC_BRAKE': 0,
427
})
428
429
self.arm_vehicle()
430
431
distance_without_brakes = self.drive_brake_get_stopping_distance(15)
432
433
# brakes on:
434
self.set_parameter('ATC_BRAKE', 1)
435
distance_with_brakes = self.drive_brake_get_stopping_distance(15)
436
437
delta = distance_without_brakes - distance_with_brakes
438
439
self.disarm_vehicle()
440
441
if delta < distance_without_brakes * 0.05: # 5% isn't asking for much
442
raise NotAchievedException("""
443
Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
444
""" %
445
(distance_with_brakes,
446
distance_without_brakes,
447
delta))
448
449
self.progress(
450
"Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" %
451
(distance_with_brakes, distance_without_brakes, delta))
452
453
def drive_rtl_mission_max_distance_from_home(self):
454
'''maximum distance allowed from home at end'''
455
return 6.5
456
457
def DriveRTL(self, timeout=120):
458
'''Drive an RTL Mission'''
459
self.wait_ready_to_arm()
460
self.arm_vehicle()
461
462
self.load_mission("rtl.txt")
463
self.change_mode("AUTO")
464
465
tstart = self.get_sim_time()
466
while True:
467
now = self.get_sim_time_cached()
468
if now - tstart > timeout:
469
raise AutoTestTimeoutException("Didn't see wp 3")
470
m = self.mav.recv_match(type='MISSION_CURRENT',
471
blocking=True,
472
timeout=1)
473
self.progress("MISSION_CURRENT: %s" % str(m))
474
if m.seq == 3:
475
break
476
477
self.drain_mav()
478
479
m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=1)
480
481
wp_dist_min = 5
482
if m.wp_dist < wp_dist_min:
483
raise PreconditionFailedException(
484
"Did not start at least %f metres from destination (is=%f)" %
485
(wp_dist_min, m.wp_dist))
486
487
self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" %
488
(m.wp_dist, wp_dist_min,))
489
490
# wait for mission to complete
491
self.wait_statustext("Mission Complete", timeout=70)
492
493
# the EKF doesn't pull us down to 0 speed:
494
self.wait_groundspeed(0, 0.5, timeout=600)
495
496
# current Rover blows straight past the home position and ends
497
# up ~6m past the home point.
498
home_distance = self.distance_to_home()
499
home_distance_min = 5.5
500
home_distance_max = self.drive_rtl_mission_max_distance_from_home()
501
if home_distance > home_distance_max:
502
raise NotAchievedException(
503
"Did not stop near home (%f metres distant (%f > want > %f))" %
504
(home_distance, home_distance_min, home_distance_max))
505
self.disarm_vehicle()
506
self.progress("RTL Mission OK (%fm)" % home_distance)
507
508
def RTL_SPEED(self, timeout=120):
509
'''Test RTL_SPEED is honoured'''
510
511
self.upload_simple_relhome_mission([
512
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 0, 0),
513
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 0),
514
])
515
516
self.wait_ready_to_arm()
517
self.arm_vehicle()
518
519
self.change_mode('AUTO')
520
self.wait_current_waypoint(2, timeout=120)
521
for speed in 1, 5.5, 1.5, 7.5:
522
self.set_parameter("RTL_SPEED", speed)
523
self.change_mode('RTL')
524
self.wait_groundspeed(speed-0.1, speed+0.1, minimum_duration=10)
525
self.change_mode('HOLD')
526
self.do_RTL()
527
self.disarm_vehicle()
528
529
def AC_Avoidance(self):
530
'''Test AC Avoidance switch'''
531
self.load_fence("rover-fence-ac-avoid.txt")
532
self.set_parameters({
533
"FENCE_ENABLE": 0,
534
"PRX1_TYPE": 10,
535
"RC10_OPTION": 40, # proximity-enable
536
})
537
self.reboot_sitl()
538
# start = self.mav.location()
539
self.wait_ready_to_arm()
540
self.arm_vehicle()
541
# first make sure we can breach the fence:
542
self.set_rc(10, 1000)
543
self.change_mode("ACRO")
544
self.set_rc(3, 1550)
545
self.wait_distance_to_home(25, 100000, timeout=60)
546
self.change_mode("RTL")
547
self.wait_statustext("Reached destination", timeout=60)
548
# now enable avoidance and make sure we can't:
549
self.set_rc(10, 2000)
550
self.change_mode("ACRO")
551
self.wait_groundspeed(0, 0.7, timeout=60)
552
# watch for speed zero
553
self.wait_groundspeed(0, 0.2, timeout=120)
554
self.disarm_vehicle()
555
556
def ServoRelayEvents(self):
557
'''Test ServoRelayEvents'''
558
for method in self.run_cmd, self.run_cmd_int:
559
self.context_push()
560
561
self.set_parameters({
562
"RELAY1_FUNCTION": 1, # Enable relay 1 as a standard relay pin
563
"RELAY2_FUNCTION": 1, # Enable relay 2 as a standard relay pin
564
})
565
self.reboot_sitl() # Needed for relay functions to take effect
566
567
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
568
off = self.get_parameter("SIM_PIN_MASK")
569
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
570
on = self.get_parameter("SIM_PIN_MASK")
571
if on == off:
572
raise NotAchievedException(
573
"Pin mask unchanged after relay cmd")
574
self.progress("Pin mask changed after relay command")
575
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
576
577
self.set_message_rate_hz("RELAY_STATUS", 10)
578
579
# default configuration for relays in sim have one relay:
580
self.assert_received_message_field_values('RELAY_STATUS', {
581
"present": 3,
582
"on": 0,
583
})
584
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
585
self.assert_received_message_field_values('RELAY_STATUS', {
586
"present": 3,
587
"on": 1,
588
})
589
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=1)
590
self.assert_received_message_field_values('RELAY_STATUS', {
591
"present": 3,
592
"on": 3,
593
})
594
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
595
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=0)
596
self.assert_received_message_field_values('RELAY_STATUS', {
597
"present": 3,
598
"on": 0,
599
})
600
601
# add another relay and ensure that it changes the "present field"
602
self.set_parameters({
603
"RELAY6_FUNCTION": 1, # Enable relay 6 as a standard relay pin
604
"RELAY6_PIN": 14, # Set pin number
605
})
606
self.reboot_sitl() # Needed for relay function to take effect
607
self.set_message_rate_hz("RELAY_STATUS", 10) # Need to re-request the message since reboot
608
609
self.assert_received_message_field_values('RELAY_STATUS', {
610
"present": 35,
611
"on": 0,
612
})
613
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=1)
614
self.assert_received_message_field_values('RELAY_STATUS', {
615
"present": 35,
616
"on": 32,
617
})
618
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
619
self.assert_received_message_field_values('RELAY_STATUS', {
620
"present": 35,
621
"on": 33,
622
})
623
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=0)
624
self.assert_received_message_field_values('RELAY_STATUS', {
625
"present": 35,
626
"on": 1,
627
})
628
629
self.start_subtest("test MAV_CMD_DO_REPEAT_RELAY")
630
self.context_push()
631
self.set_parameter("SIM_SPEEDUP", 1)
632
method(
633
mavutil.mavlink.MAV_CMD_DO_REPEAT_RELAY,
634
p1=0, # servo 1
635
p2=5, # 5 times
636
p3=0.5, # 1 second between being on
637
)
638
for value in 0, 1, 0, 1, 0, 1, 0, 1:
639
self.wait_message_field_values('RELAY_STATUS', {
640
"on": value,
641
})
642
self.context_pop()
643
self.delay_sim_time(3)
644
self.assert_received_message_field_values('RELAY_STATUS', {
645
"on": 1, # back to initial state
646
})
647
self.context_pop()
648
649
self.start_subtest("test MAV_CMD_DO_SET_SERVO")
650
for value in 1678, 2300, 0:
651
method(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=13, p2=value)
652
self.wait_servo_channel_value(13, value)
653
654
self.start_subtest("test MAV_CMD_DO_REPEAT_SERVO")
655
656
self.context_push()
657
self.set_parameter("SIM_SPEEDUP", 1)
658
trim = self.get_parameter("SERVO13_TRIM")
659
value = 2000
660
method(
661
mavutil.mavlink.MAV_CMD_DO_REPEAT_SERVO,
662
p1=12, # servo12
663
p2=value, # pwm
664
p3=5, # count
665
p4=0.5, # cycle time (1 second between high and high)
666
)
667
for value in trim, value, trim, value, trim, value, trim, value:
668
self.wait_servo_channel_value(12, value)
669
self.context_pop()
670
671
self.set_message_rate_hz("RELAY_STATUS", 0)
672
673
def MAVProxy_SetModeUsingSwitch(self):
674
"""Set modes via mavproxy switch"""
675
port = self.sitl_rcin_port(offset=1)
676
self.customise_SITL_commandline([
677
"--rc-in-port", str(port),
678
])
679
ex = None
680
try:
681
self.load_mission(self.arming_test_mission())
682
self.wait_ready_to_arm()
683
fnoo = [(1, 'MANUAL'),
684
(2, 'MANUAL'),
685
(3, 'RTL'),
686
(4, 'AUTO'),
687
(5, 'AUTO'), # non-existant mode, should stay in RTL
688
(6, 'MANUAL')]
689
mavproxy = self.start_mavproxy(sitl_rcin_port=port)
690
for (num, expected) in fnoo:
691
mavproxy.send('switch %u\n' % num)
692
self.wait_mode(expected)
693
self.stop_mavproxy(mavproxy)
694
except Exception as e:
695
self.print_exception_caught(e)
696
ex = e
697
698
# if we don't put things back ourselves then the test cleanup
699
# doesn't go well as we can't set the RC defaults correctly:
700
self.customise_SITL_commandline([
701
])
702
703
if ex is not None:
704
raise ex
705
706
def MAVProxy_SetModeUsingMode(self):
707
'''Set modes via mavproxy mode command'''
708
fnoo = [(1, 'ACRO'),
709
(3, 'STEERING'),
710
(4, 'HOLD'),
711
]
712
mavproxy = self.start_mavproxy()
713
for (num, expected) in fnoo:
714
mavproxy.send('mode manual\n')
715
self.wait_mode("MANUAL")
716
mavproxy.send('mode %u\n' % num)
717
self.wait_mode(expected)
718
mavproxy.send('mode manual\n')
719
self.wait_mode("MANUAL")
720
mavproxy.send('mode %s\n' % expected)
721
self.wait_mode(expected)
722
self.stop_mavproxy(mavproxy)
723
724
def ModeSwitch(self):
725
''''Set modes via modeswitch'''
726
self.set_parameter("MODE_CH", 8)
727
self.set_rc(8, 1000)
728
# mavutil.mavlink.ROVER_MODE_HOLD:
729
self.set_parameter("MODE6", 4)
730
# mavutil.mavlink.ROVER_MODE_ACRO
731
self.set_parameter("MODE5", 1)
732
self.set_rc(8, 1800) # PWM for mode6
733
self.wait_mode("HOLD")
734
self.set_rc(8, 1700) # PWM for mode5
735
self.wait_mode("ACRO")
736
self.set_rc(8, 1800) # PWM for mode6
737
self.wait_mode("HOLD")
738
self.set_rc(8, 1700) # PWM for mode5
739
self.wait_mode("ACRO")
740
741
def AuxModeSwitch(self):
742
'''Set modes via auxswitches'''
743
# from mavproxy_rc.py
744
mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815]
745
self.set_parameter("MODE1", 1) # acro
746
self.set_rc(8, mapping[1])
747
self.wait_mode('ACRO')
748
749
self.set_rc(9, 1000)
750
self.set_rc(10, 1000)
751
self.set_parameters({
752
"RC9_OPTION": 53, # steering
753
"RC10_OPTION": 54, # hold
754
})
755
self.set_rc(9, 1900)
756
self.wait_mode("STEERING")
757
self.set_rc(10, 1900)
758
self.wait_mode("HOLD")
759
760
# reset both switches - should go back to ACRO
761
self.set_rc(9, 1000)
762
self.set_rc(10, 1000)
763
self.wait_mode("ACRO")
764
765
self.set_rc(9, 1900)
766
self.wait_mode("STEERING")
767
self.set_rc(10, 1900)
768
self.wait_mode("HOLD")
769
770
self.set_rc(10, 1000) # this re-polls the mode switch
771
self.wait_mode("ACRO")
772
self.set_rc(9, 1000)
773
774
def RCOverridesCancel(self):
775
'''Test RC overrides Cancel'''
776
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
777
self.change_mode('MANUAL')
778
self.wait_ready_to_arm()
779
self.zero_throttle()
780
self.arm_vehicle()
781
# start moving forward a little:
782
normal_rc_throttle = 1700
783
throttle_override = 1900
784
785
self.progress("Establishing baseline RC input")
786
self.set_rc(3, normal_rc_throttle)
787
self.drain_mav()
788
tstart = self.get_sim_time()
789
while True:
790
if self.get_sim_time_cached() - tstart > 10:
791
raise AutoTestTimeoutException("Did not get rc change")
792
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
793
if m.chan3_raw == normal_rc_throttle:
794
break
795
796
self.progress("Set override with RC_CHANNELS_OVERRIDE")
797
self.drain_mav()
798
tstart = self.get_sim_time()
799
while True:
800
if self.get_sim_time_cached() - tstart > 10:
801
raise AutoTestTimeoutException("Did not override")
802
self.progress("Sending throttle of %u" % (throttle_override,))
803
self.mav.mav.rc_channels_override_send(
804
1, # target system
805
1, # targe component
806
65535, # chan1_raw
807
65535, # chan2_raw
808
throttle_override, # chan3_raw
809
65535, # chan4_raw
810
65535, # chan5_raw
811
65535, # chan6_raw
812
65535, # chan7_raw
813
65535) # chan8_raw
814
815
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
816
self.progress("chan3=%f want=%f" % (m.chan3_raw, throttle_override))
817
if m.chan3_raw == throttle_override:
818
break
819
820
self.progress("disabling override and making sure we revert to RC input in good time")
821
self.drain_mav()
822
tstart = self.get_sim_time()
823
while True:
824
if self.get_sim_time_cached() - tstart > 0.5:
825
raise AutoTestTimeoutException("Did not cancel override")
826
self.progress("Sending cancel of throttle override")
827
self.mav.mav.rc_channels_override_send(
828
1, # target system
829
1, # targe component
830
65535, # chan1_raw
831
65535, # chan2_raw
832
0, # chan3_raw
833
65535, # chan4_raw
834
65535, # chan5_raw
835
65535, # chan6_raw
836
65535, # chan7_raw
837
65535) # chan8_raw
838
self.do_timesync_roundtrip()
839
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True)
840
self.progress("chan3=%f want=%f" % (m.chan3_raw, normal_rc_throttle))
841
if m.chan3_raw == normal_rc_throttle:
842
break
843
self.disarm_vehicle()
844
845
def RCOverrides(self):
846
'''Test RC overrides'''
847
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
848
self.set_parameter("RC12_OPTION", 46)
849
self.reboot_sitl()
850
851
self.change_mode('MANUAL')
852
self.wait_ready_to_arm()
853
self.set_rc(3, 1500) # throttle at zero
854
self.arm_vehicle()
855
# start moving forward a little:
856
normal_rc_throttle = 1700
857
self.set_rc(3, normal_rc_throttle)
858
self.wait_groundspeed(5, 100)
859
860
# allow overrides:
861
self.set_rc(12, 2000)
862
863
# now override to stop:
864
throttle_override = 1500
865
866
tstart = self.get_sim_time_cached()
867
while True:
868
if self.get_sim_time_cached() - tstart > 10:
869
raise AutoTestTimeoutException("Did not reach speed")
870
self.progress("Sending throttle of %u" % (throttle_override,))
871
self.mav.mav.rc_channels_override_send(
872
1, # target system
873
1, # targe component
874
65535, # chan1_raw
875
65535, # chan2_raw
876
throttle_override, # chan3_raw
877
65535, # chan4_raw
878
65535, # chan5_raw
879
65535, # chan6_raw
880
65535, # chan7_raw
881
65535) # chan8_raw
882
883
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
884
want_speed = 2.0
885
self.progress("Speed=%f want=<%f" % (m.groundspeed, want_speed))
886
if m.groundspeed < want_speed:
887
break
888
889
# now override to stop - but set the switch on the RC
890
# transmitter to deny overrides; this should send the
891
# speed back up to 5 metres/second:
892
self.set_rc(12, 1000)
893
894
throttle_override = 1500
895
tstart = self.get_sim_time_cached()
896
while True:
897
if self.get_sim_time_cached() - tstart > 10:
898
raise AutoTestTimeoutException("Did not speed back up")
899
self.progress("Sending throttle of %u" % (throttle_override,))
900
self.mav.mav.rc_channels_override_send(
901
1, # target system
902
1, # targe component
903
65535, # chan1_raw
904
65535, # chan2_raw
905
throttle_override, # chan3_raw
906
65535, # chan4_raw
907
65535, # chan5_raw
908
65535, # chan6_raw
909
65535, # chan7_raw
910
65535) # chan8_raw
911
912
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
913
want_speed = 5.0
914
self.progress("Speed=%f want=>%f" % (m.groundspeed, want_speed))
915
916
if m.groundspeed > want_speed:
917
break
918
919
# re-enable RC overrides
920
self.set_rc(12, 2000)
921
922
# check we revert to normal RC inputs when gcs overrides cease:
923
self.progress("Waiting for RC to revert to normal RC input")
924
self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)
925
926
self.start_subtest("Check override time of zero disables overrides")
927
old = self.get_parameter("RC_OVERRIDE_TIME")
928
ch = 2
929
self.set_rc(ch, 1000)
930
channels = [65535] * 18
931
ch_override_value = 1700
932
channels[ch-1] = ch_override_value
933
channels[7] = 1234 # that's channel 8!
934
self.progress("Sending override message %u" % ch_override_value)
935
self.mav.mav.rc_channels_override_send(
936
1, # target system
937
1, # targe component
938
*channels
939
)
940
# long timeout required here as we may have sent a lot of
941
# things via MAVProxy...
942
self.wait_rc_channel_value(ch, ch_override_value, timeout=30)
943
self.set_parameter("RC_OVERRIDE_TIME", 0)
944
self.wait_rc_channel_value(ch, 1000)
945
self.set_parameter("RC_OVERRIDE_TIME", old)
946
self.wait_rc_channel_value(ch, ch_override_value)
947
948
ch_override_value = 1720
949
channels[ch-1] = ch_override_value
950
self.progress("Sending override message %u" % ch_override_value)
951
self.mav.mav.rc_channels_override_send(
952
1, # target system
953
1, # targe component
954
*channels
955
)
956
self.wait_rc_channel_value(ch, ch_override_value, timeout=10)
957
self.set_parameter("RC_OVERRIDE_TIME", 0)
958
self.wait_rc_channel_value(ch, 1000)
959
self.set_parameter("RC_OVERRIDE_TIME", old)
960
961
self.progress("Ensuring timeout works")
962
self.wait_rc_channel_value(ch, 1000, timeout=5)
963
self.delay_sim_time(10)
964
965
self.set_parameter("RC_OVERRIDE_TIME", 10)
966
self.progress("Sending override message")
967
968
ch_override_value = 1730
969
channels[ch-1] = ch_override_value
970
self.progress("Sending override message %u" % ch_override_value)
971
self.mav.mav.rc_channels_override_send(
972
1, # target system
973
1, # targe component
974
*channels
975
)
976
self.wait_rc_channel_value(ch, ch_override_value, timeout=10)
977
tstart = self.get_sim_time()
978
self.progress("Waiting for channel to revert to 1000 in ~10s")
979
self.wait_rc_channel_value(ch, 1000, timeout=15)
980
delta = self.get_sim_time() - tstart
981
if delta > 12:
982
raise NotAchievedException("Took too long to revert RC channel value (delta=%f)" % delta)
983
min_delta = 9
984
if delta < min_delta:
985
raise NotAchievedException("Didn't take long enough to revert RC channel value (delta=%f want>=%f)" %
986
(delta, min_delta))
987
self.progress("Disabling RC override timeout")
988
self.set_parameter("RC_OVERRIDE_TIME", -1)
989
ch_override_value = 1740
990
channels[ch-1] = ch_override_value
991
self.progress("Sending override message %u" % ch_override_value)
992
self.mav.mav.rc_channels_override_send(
993
1, # target system
994
1, # targe component
995
*channels
996
)
997
self.wait_rc_channel_value(ch, ch_override_value, timeout=10)
998
tstart = self.get_sim_time()
999
while True:
1000
# warning: this is get_sim_time() and can slurp messages on you!
1001
delta = self.get_sim_time() - tstart
1002
if delta > 20:
1003
break
1004
m = self.assert_receive_message('RC_CHANNELS', timeout=1)
1005
channel_field = "chan%u_raw" % ch
1006
m_value = getattr(m, channel_field)
1007
if m_value != ch_override_value:
1008
raise NotAchievedException("Value reverted after %f seconds when it should not have (got=%u) (want=%u)" % (delta, m_value, ch_override_value)) # noqa
1009
self.set_parameter("RC_OVERRIDE_TIME", old)
1010
1011
self.delay_sim_time(10)
1012
1013
self.start_subtest("Checking higher-channel semantics")
1014
self.context_push()
1015
self.set_parameter("RC_OVERRIDE_TIME", 30)
1016
1017
ch = 11
1018
rc_value = 1010
1019
self.set_rc(ch, rc_value)
1020
1021
channels = [65535] * 18
1022
ch_override_value = 1234
1023
channels[ch-1] = ch_override_value
1024
self.progress("Sending override message ch%u=%u" % (ch, ch_override_value))
1025
self.mav.mav.rc_channels_override_send(
1026
1, # target system
1027
1, # targe component
1028
*channels
1029
)
1030
self.progress("Wait for override value")
1031
self.wait_rc_channel_value(ch, ch_override_value, timeout=10)
1032
1033
self.progress("Sending return-to-RC-input value")
1034
channels[ch-1] = 65534
1035
self.mav.mav.rc_channels_override_send(
1036
1, # target system
1037
1, # targe component
1038
*channels
1039
)
1040
self.wait_rc_channel_value(ch, rc_value, timeout=10)
1041
1042
channels[ch-1] = ch_override_value
1043
self.progress("Sending override message ch%u=%u" % (ch, ch_override_value))
1044
self.mav.mav.rc_channels_override_send(
1045
1, # target system
1046
1, # targe component
1047
*channels
1048
)
1049
self.progress("Wait for override value")
1050
self.wait_rc_channel_value(ch, ch_override_value, timeout=10)
1051
1052
# make we keep the override vaue for at least 10 seconds:
1053
tstart = self.get_sim_time()
1054
while True:
1055
if self.get_sim_time_cached() - tstart > 10:
1056
break
1057
# try both ignore values:
1058
ignore_value = 0
1059
if self.get_sim_time_cached() - tstart > 5:
1060
ignore_value = 65535
1061
self.progress("Sending ignore value %u" % ignore_value)
1062
channels[ch-1] = ignore_value
1063
self.mav.mav.rc_channels_override_send(
1064
1, # target system
1065
1, # targe component
1066
*channels
1067
)
1068
if self.get_rc_channel_value(ch) != ch_override_value:
1069
raise NotAchievedException("Did not maintain value")
1070
1071
self.context_pop()
1072
1073
self.end_subtest("Checking higher-channel semantics")
1074
1075
self.disarm_vehicle()
1076
1077
def MANUAL_CONTROL(self):
1078
'''Test mavlink MANUAL_CONTROL'''
1079
self.set_parameters({
1080
"SYSID_MYGCS": self.mav.source_system,
1081
"RC12_OPTION": 46, # enable/disable rc overrides
1082
})
1083
self.reboot_sitl()
1084
1085
self.change_mode("MANUAL")
1086
self.wait_ready_to_arm()
1087
self.arm_vehicle()
1088
self.progress("start moving forward a little")
1089
normal_rc_throttle = 1700
1090
self.set_rc(3, normal_rc_throttle)
1091
self.wait_groundspeed(5, 100)
1092
1093
self.progress("allow overrides")
1094
self.set_rc(12, 2000)
1095
1096
self.progress("now override to stop")
1097
throttle_override_normalized = 0
1098
expected_throttle = 0 # in VFR_HUD
1099
1100
tstart = self.get_sim_time_cached()
1101
while True:
1102
if self.get_sim_time_cached() - tstart > 10:
1103
raise AutoTestTimeoutException("Did not reach speed")
1104
self.progress("Sending normalized throttle of %d" % (throttle_override_normalized,))
1105
self.mav.mav.manual_control_send(
1106
1, # target system
1107
32767, # x (pitch)
1108
32767, # y (roll)
1109
throttle_override_normalized, # z (thrust)
1110
32767, # r (yaw)
1111
0) # button mask
1112
1113
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
1114
want_speed = 2.0
1115
self.progress("Speed=%f want=<%f throttle=%u want=%u" %
1116
(m.groundspeed, want_speed, m.throttle, expected_throttle))
1117
if m.groundspeed < want_speed and m.throttle == expected_throttle:
1118
break
1119
1120
self.progress("now override to stop - but set the switch on the RC transmitter to deny overrides; this should send the speed back up to 5 metres/second") # noqa
1121
self.set_rc(12, 1000)
1122
1123
throttle_override_normalized = 500
1124
expected_throttle = 36 # in VFR_HUD, corresponding to normal_rc_throttle adjusted for channel min/max
1125
1126
tstart = self.get_sim_time_cached()
1127
while True:
1128
if self.get_sim_time_cached() - tstart > 10:
1129
raise AutoTestTimeoutException("Did not stop")
1130
self.progress("Sending normalized throttle of %u" % (throttle_override_normalized,))
1131
self.mav.mav.manual_control_send(
1132
1, # target system
1133
32767, # x (pitch)
1134
32767, # y (roll)
1135
throttle_override_normalized, # z (thrust)
1136
32767, # r (yaw)
1137
0) # button mask
1138
1139
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
1140
want_speed = 5.0
1141
1142
self.progress("Speed=%f want=>%f throttle=%u want=%u" %
1143
(m.groundspeed, want_speed, m.throttle, expected_throttle))
1144
if m.groundspeed > want_speed and m.throttle == expected_throttle:
1145
break
1146
1147
# re-enable RC overrides
1148
self.set_rc(12, 2000)
1149
1150
# check we revert to normal RC inputs when gcs overrides cease:
1151
self.progress("Waiting for RC to revert to normal RC input")
1152
self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)
1153
1154
self.disarm_vehicle()
1155
1156
def CameraMission(self):
1157
'''Test Camera Mission Items'''
1158
self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger
1159
self.reboot_sitl() # needed for CAM1_TYPE to take effect
1160
self.load_mission("rover-camera-mission.txt")
1161
self.wait_ready_to_arm()
1162
self.change_mode("AUTO")
1163
self.wait_ready_to_arm()
1164
self.arm_vehicle()
1165
prev_cf = None
1166
while True:
1167
cf = self.mav.recv_match(type='CAMERA_FEEDBACK', blocking=True)
1168
if prev_cf is None:
1169
prev_cf = cf
1170
continue
1171
dist_travelled = self.get_distance_int(prev_cf, cf)
1172
prev_cf = cf
1173
mc = self.mav.messages.get("MISSION_CURRENT", None)
1174
if mc is None:
1175
continue
1176
elif mc.seq == 2:
1177
expected_distance = 2
1178
elif mc.seq == 4:
1179
expected_distance = 5
1180
elif mc.seq == 5:
1181
break
1182
else:
1183
continue
1184
self.progress("Expected distance %f got %f" %
1185
(expected_distance, dist_travelled))
1186
error = abs(expected_distance - dist_travelled)
1187
# Rover moves at ~5m/s; we appear to do something at
1188
# 5Hz, so we do see over a meter of error!
1189
max_error = 1.5
1190
if error > max_error:
1191
raise NotAchievedException("Camera distance error: %f (%f)" %
1192
(error, max_error))
1193
1194
self.disarm_vehicle()
1195
1196
def DO_SET_MODE(self):
1197
'''Set mode via MAV_COMMAND_DO_SET_MODE'''
1198
self.do_set_mode_via_command_long("HOLD")
1199
self.do_set_mode_via_command_long("MANUAL")
1200
self.do_set_mode_via_command_int("HOLD")
1201
self.do_set_mode_via_command_int("MANUAL")
1202
1203
def RoverInitialMode(self):
1204
'''test INITIAL_MODE parameter works'''
1205
# from mavproxy_rc.py
1206
self.wait_ready_to_arm()
1207
mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815]
1208
mode_ch = 8
1209
throttle_ch = 3
1210
self.set_parameter('MODE5', 3)
1211
self.set_rc(mode_ch, mapping[5])
1212
self.wait_mode('STEERING')
1213
self.set_rc(mode_ch, mapping[6])
1214
self.wait_mode('MANUAL')
1215
self.set_parameter("INITIAL_MODE", 1) # acro
1216
# stop the vehicle polling the mode switch at boot:
1217
self.set_parameter('FS_ACTION', 0) # do nothing when radio fails
1218
self.set_rc(throttle_ch, 900) # RC fail
1219
self.reboot_sitl()
1220
self.wait_mode(1)
1221
self.progress("Make sure we stay in this mode")
1222
self.delay_sim_time(5)
1223
self.wait_mode(1)
1224
# now change modes with a switch:
1225
self.set_rc(throttle_ch, 1100)
1226
self.delay_sim_time(3)
1227
self.set_rc(mode_ch, mapping[5])
1228
self.wait_mode('STEERING')
1229
1230
def MAVProxy_DO_SET_MODE(self):
1231
'''Set mode using MAVProxy commandline DO_SET_MODE'''
1232
mavproxy = self.start_mavproxy()
1233
self.mavproxy_do_set_mode_via_command_long(mavproxy, "HOLD")
1234
self.mavproxy_do_set_mode_via_command_long(mavproxy, "MANUAL")
1235
self.stop_mavproxy(mavproxy)
1236
1237
def SYSID_ENFORCE(self):
1238
'''Test enforcement of SYSID_MYGCS'''
1239
'''Run the same arming code with correct then incorrect SYSID'''
1240
1241
if self.mav.source_system != self.mav.mav.srcSystem:
1242
raise PreconditionFailedException("Expected mav.source_system and mav.srcSystem to match")
1243
1244
self.context_push()
1245
old_srcSystem = self.mav.mav.srcSystem
1246
ex = None
1247
try:
1248
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
1249
self.set_parameter("SYSID_ENFORCE", 1, add_to_context=False)
1250
1251
self.change_mode('MANUAL')
1252
1253
self.progress("make sure I can arm ATM")
1254
self.wait_ready_to_arm()
1255
self.arm_vehicle(timeout=5)
1256
self.disarm_vehicle()
1257
1258
self.do_timesync_roundtrip()
1259
1260
# should not be able to arm from a system id which is not MY_SYSID
1261
self.progress("Attempting to arm vehicle from bad system-id")
1262
success = None
1263
try:
1264
# temporarily set a different system ID than normal:
1265
self.mav.mav.srcSystem = 72
1266
self.arm_vehicle(timeout=5)
1267
self.disarm_vehicle()
1268
success = False
1269
except AutoTestTimeoutException:
1270
success = True
1271
self.mav.mav.srcSystem = old_srcSystem
1272
if not success:
1273
raise NotAchievedException("Managed to arm with SYSID_ENFORCE set")
1274
1275
# should be able to arm from the vehicle's own components:
1276
self.progress("Attempting to arm vehicle from vehicle component")
1277
comp_arm_exception = None
1278
try:
1279
self.mav.mav.srcSystem = 1
1280
self.arm_vehicle(timeout=5)
1281
self.disarm_vehicle()
1282
except Exception as e:
1283
comp_arm_exception = e
1284
self.mav.mav.srcSystem = old_srcSystem
1285
if comp_arm_exception is not None:
1286
raise comp_arm_exception
1287
1288
except Exception as e:
1289
self.print_exception_caught(e)
1290
ex = e
1291
self.mav.mav.srcSystem = old_srcSystem
1292
self.set_parameter("SYSID_ENFORCE", 0, add_to_context=False)
1293
self.context_pop()
1294
if ex is not None:
1295
raise ex
1296
1297
def Rally(self):
1298
'''Test Rally Points'''
1299
self.load_rally_using_mavproxy("rover-test-rally.txt")
1300
self.assert_parameter_value('RALLY_TOTAL', 2)
1301
1302
self.wait_ready_to_arm()
1303
self.arm_vehicle()
1304
1305
# calculate early to avoid round-trips while vehicle is moving:
1306
accuracy = self.get_parameter("WP_RADIUS")
1307
1308
self.reach_heading_manual(10)
1309
self.reach_distance_manual(50)
1310
1311
self.change_mode("RTL")
1312
1313
# location copied in from rover-test-rally.txt:
1314
loc = mavutil.location(40.071553,
1315
-105.229401,
1316
1583,
1317
0)
1318
1319
self.wait_location(loc, accuracy=accuracy, minimum_duration=10, timeout=45)
1320
self.disarm_vehicle()
1321
1322
def fence_with_bad_frame(self, target_system=1, target_component=1):
1323
return [
1324
self.mav.mav.mission_item_int_encode(
1325
target_system,
1326
target_component,
1327
0, # seq
1328
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
1329
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1330
0, # current
1331
0, # autocontinue
1332
0, # p1
1333
0, # p2
1334
0, # p3
1335
0, # p4
1336
int(1.0017 * 1e7), # latitude
1337
int(1.0017 * 1e7), # longitude
1338
31.0000, # altitude
1339
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1340
]
1341
1342
def fence_with_zero_vertex_count(self, target_system=1, target_component=1):
1343
return [
1344
self.mav.mav.mission_item_int_encode(
1345
target_system,
1346
target_component,
1347
0, # seq
1348
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1349
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1350
0, # current
1351
0, # autocontinue
1352
0, # p1
1353
0, # p2
1354
0, # p3
1355
0, # p4
1356
int(1.0017 * 1e7), # latitude
1357
int(1.0017 * 1e7), # longitude
1358
31.0000, # altitude
1359
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1360
]
1361
1362
def fence_with_wrong_vertex_count(self, target_system=1, target_component=1):
1363
return [
1364
self.mav.mav.mission_item_int_encode(
1365
target_system,
1366
target_component,
1367
0, # seq
1368
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1369
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1370
0, # current
1371
0, # autocontinue
1372
2, # p1
1373
0, # p2
1374
0, # p3
1375
0, # p4
1376
int(1.0017 * 1e7), # latitude
1377
int(1.0017 * 1e7), # longitude
1378
31.0000, # altitude
1379
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1380
]
1381
1382
def fence_with_multiple_return_points(self, target_system=1, target_component=1):
1383
return [
1384
self.mav.mav.mission_item_int_encode(
1385
target_system,
1386
target_component,
1387
0, # seq
1388
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1389
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1390
0, # current
1391
0, # autocontinue
1392
0, # p1
1393
0, # p2
1394
0, # p3
1395
0, # p4
1396
int(1.0017 * 1e7), # latitude
1397
int(1.0017 * 1e7), # longitude
1398
31.0000, # altitude
1399
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1400
self.mav.mav.mission_item_int_encode(
1401
target_system,
1402
target_component,
1403
1, # seq
1404
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1405
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1406
0, # current
1407
0, # autocontinue
1408
0, # p1
1409
0, # p2
1410
0, # p3
1411
0, # p4
1412
int(1.0017 * 1e7), # latitude
1413
int(1.0017 * 1e7), # longitude
1414
31.0000, # altitude
1415
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1416
]
1417
1418
def fence_with_invalid_latlon(self, target_system=1, target_component=1):
1419
return [
1420
self.mav.mav.mission_item_int_encode(
1421
target_system,
1422
target_component,
1423
0, # seq
1424
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1425
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1426
0, # current
1427
0, # autocontinue
1428
0, # p1
1429
0, # p2
1430
0, # p3
1431
0, # p4
1432
int(100 * 1e7), # bad latitude. bad.
1433
int(1.0017 * 1e7), # longitude
1434
31.0000, # altitude
1435
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1436
]
1437
1438
def fence_with_multiple_return_points_with_bad_sequence_numbers(self, target_system=1, target_component=1):
1439
return [
1440
self.mav.mav.mission_item_int_encode(
1441
target_system,
1442
target_component,
1443
0, # seq
1444
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1445
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1446
0, # current
1447
0, # autocontinue
1448
0, # p1
1449
0, # p2
1450
0, # p3
1451
0, # p4
1452
int(1.0 * 1e7), # latitude
1453
int(1.0017 * 1e7), # longitude
1454
31.0000, # altitude
1455
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1456
self.mav.mav.mission_item_int_encode(
1457
target_system,
1458
target_component,
1459
0, # seq
1460
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1461
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1462
0, # current
1463
0, # autocontinue
1464
0, # p1
1465
0, # p2
1466
0, # p3
1467
0, # p4
1468
int(2.0 * 1e7), # latitude
1469
int(2.0017 * 1e7), # longitude
1470
31.0000, # altitude
1471
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1472
]
1473
1474
def fence_which_exceeds_storage_space(self, target_system=1, target_component=1):
1475
ret = []
1476
for i in range(0, 60):
1477
ret.append(self.mav.mav.mission_item_int_encode(
1478
target_system,
1479
target_component,
1480
i, # seq
1481
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1482
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
1483
0, # current
1484
0, # autocontinue
1485
10, # p1
1486
0, # p2
1487
0, # p3
1488
0, # p4
1489
int(1.0 * 1e7), # latitude
1490
int(1.0017 * 1e7), # longitude
1491
31.0000, # altitude
1492
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1493
)
1494
return ret
1495
1496
def fences_which_should_not_upload(self, target_system=1, target_component=1):
1497
return [
1498
("Bad Frame", self.fence_with_bad_frame(
1499
target_system=target_system,
1500
target_component=target_component)),
1501
("Zero Vertex Count", self.fence_with_zero_vertex_count(
1502
target_system=target_system,
1503
target_component=target_component)),
1504
("Wrong Vertex Count", self.fence_with_wrong_vertex_count(
1505
target_system=target_system,
1506
target_component=target_component)),
1507
("Multiple return points", self.fence_with_multiple_return_points(
1508
target_system=target_system,
1509
target_component=target_component)),
1510
("Invalid lat/lon", self.fence_with_invalid_latlon(
1511
target_system=target_system,
1512
target_component=target_component)),
1513
("Multiple Return points with bad sequence numbers",
1514
self.fence_with_multiple_return_points_with_bad_sequence_numbers( # noqa
1515
target_system=target_system,
1516
target_component=target_component)),
1517
("Fence which exceeds storage space",
1518
self.fence_which_exceeds_storage_space(
1519
target_system=target_system,
1520
target_component=target_component)),
1521
]
1522
1523
def fence_with_single_return_point(self, target_system=1, target_component=1):
1524
return [
1525
self.mav.mav.mission_item_int_encode(
1526
target_system,
1527
target_component,
1528
0, # seq
1529
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1530
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1531
0, # current
1532
0, # autocontinue
1533
0, # p1
1534
0, # p2
1535
0, # p3
1536
0, # p4
1537
int(1.0017 * 1e7), # latitude
1538
int(1.0017 * 1e7), # longitude
1539
31.0000, # altitude
1540
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1541
]
1542
1543
def fence_with_single_return_point_and_5_vertex_inclusion(self,
1544
target_system=1,
1545
target_component=1):
1546
return [
1547
self.mav.mav.mission_item_int_encode(
1548
target_system,
1549
target_component,
1550
0, # seq
1551
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1552
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1553
0, # current
1554
0, # autocontinue
1555
0, # p1
1556
0, # p2
1557
0, # p3
1558
0, # p4
1559
int(1.0017 * 1e7), # latitude
1560
int(1.0017 * 1e7), # longitude
1561
31.0000, # altitude
1562
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1563
self.mav.mav.mission_item_int_encode(
1564
target_system,
1565
target_component,
1566
1, # seq
1567
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1568
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1569
0, # current
1570
0, # autocontinue
1571
5, # p1
1572
0, # p2
1573
0, # p3
1574
0, # p4
1575
int(1.0000 * 1e7), # latitude
1576
int(1.0000 * 1e7), # longitude
1577
31.0000, # altitude
1578
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1579
self.mav.mav.mission_item_int_encode(
1580
target_system,
1581
target_component,
1582
2, # seq
1583
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1584
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1585
0, # current
1586
0, # autocontinue
1587
5, # p1
1588
0, # p2
1589
0, # p3
1590
0, # p4
1591
int(1.0001 * 1e7), # latitude
1592
int(1.0000 * 1e7), # longitude
1593
32.0000, # altitude
1594
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1595
self.mav.mav.mission_item_int_encode(
1596
target_system,
1597
target_component,
1598
3, # seq
1599
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1600
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1601
0, # current
1602
0, # autocontinue
1603
5, # p1
1604
0, # p2
1605
0, # p3
1606
0, # p4
1607
int(1.0001 * 1e7), # latitude
1608
int(1.0001 * 1e7), # longitude
1609
33.0000, # altitude
1610
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1611
self.mav.mav.mission_item_int_encode(
1612
target_system,
1613
target_component,
1614
4, # seq
1615
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1616
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1617
0, # current
1618
0, # autocontinue
1619
5, # p1
1620
0, # p2
1621
0, # p3
1622
0, # p4
1623
int(1.0002 * 1e7), # latitude
1624
int(1.0002 * 1e7), # longitude
1625
33.0000, # altitude
1626
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1627
self.mav.mav.mission_item_int_encode(
1628
target_system,
1629
target_component,
1630
5, # seq
1631
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1632
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1633
0, # current
1634
0, # autocontinue
1635
5, # p1
1636
0, # p2
1637
0, # p3
1638
0, # p4
1639
int(1.0002 * 1e7), # latitude
1640
int(1.0003 * 1e7), # longitude
1641
33.0000, # altitude
1642
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1643
]
1644
1645
def fence_with_many_exclusion_circles(self, count=50, target_system=1, target_component=1):
1646
ret = []
1647
for i in range(0, count):
1648
lat_deg = 1.0003 + count/10
1649
lng_deg = 1.0002 + count/10
1650
item = self.mav.mav.mission_item_int_encode(
1651
target_system,
1652
target_component,
1653
i, # seq
1654
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1655
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
1656
0, # current
1657
0, # autocontinue
1658
count, # p1
1659
0, # p2
1660
0, # p3
1661
0, # p4
1662
int(lat_deg * 1e7), # latitude
1663
int(lng_deg * 1e7), # longitude
1664
33.0000, # altitude
1665
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1666
ret.append(item)
1667
return ret
1668
1669
def fence_with_many_exclusion_polyfences(self, target_system=1, target_component=1):
1670
ret = []
1671
seq = 0
1672
for fencenum in range(0, 4):
1673
pointcount = fencenum + 6
1674
for p in range(0, pointcount):
1675
lat_deg = 1.0003 + p/10 + fencenum/100
1676
lng_deg = 1.0002 + p/10 + fencenum/100
1677
item = self.mav.mav.mission_item_int_encode(
1678
target_system,
1679
target_component,
1680
seq, # seq
1681
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1682
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
1683
0, # current
1684
0, # autocontinue
1685
pointcount, # p1
1686
0, # p2
1687
0, # p3
1688
0, # p4
1689
int(lat_deg * 1e7), # latitude
1690
int(lng_deg * 1e7), # longitude
1691
33.0000, # altitude
1692
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1693
ret.append(item)
1694
seq += 1
1695
return ret
1696
1697
def fences_which_should_upload(self, target_system=1, target_component=1):
1698
return [
1699
("Single Return Point",
1700
self.fence_with_single_return_point(
1701
target_system=target_system,
1702
target_component=target_component)),
1703
("Return and 5-vertex-inclusion",
1704
self.fence_with_single_return_point_and_5_vertex_inclusion(
1705
target_system=target_system,
1706
target_component=target_component)),
1707
("Many exclusion circles",
1708
self.fence_with_many_exclusion_circles(
1709
target_system=target_system,
1710
target_component=target_component)),
1711
("Many exclusion polyfences",
1712
self.fence_with_many_exclusion_polyfences(
1713
target_system=target_system,
1714
target_component=target_component)),
1715
("Empty fence", []),
1716
]
1717
1718
def assert_fence_does_not_upload(self, fence, target_system=1, target_component=1):
1719
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
1720
target_system=target_system,
1721
target_component=target_component)
1722
# upload single item using mission item protocol:
1723
upload_failed = False
1724
try:
1725
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
1726
fence)
1727
except NotAchievedException:
1728
# TODO: make sure we failed for correct reason
1729
upload_failed = True
1730
if not upload_failed:
1731
raise NotAchievedException("Uploaded fence when should not be possible")
1732
self.progress("Fence rightfully bounced")
1733
1734
def send_fencepoint_expect_statustext(self,
1735
offset,
1736
count,
1737
lat,
1738
lng,
1739
statustext_fragment,
1740
target_system=1,
1741
target_component=1,
1742
timeout=10):
1743
self.mav.mav.fence_point_send(target_system,
1744
target_component,
1745
offset,
1746
count,
1747
lat,
1748
lng)
1749
1750
tstart = self.get_sim_time_cached()
1751
while True:
1752
if self.get_sim_time_cached() - tstart > timeout:
1753
raise NotAchievedException("Did not get error message back")
1754
m = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=1)
1755
self.progress("statustext: %s (want='%s')" %
1756
(str(m), statustext_fragment))
1757
if m is None:
1758
continue
1759
if statustext_fragment in m.text:
1760
break
1761
1762
def GCSFailsafe(self, side=60, timeout=360):
1763
"""Test GCS Failsafe"""
1764
try:
1765
self.test_gcs_failsafe(side=side, timeout=timeout)
1766
except Exception as ex:
1767
self.setGCSfailsafe(0)
1768
self.set_parameter('FS_ACTION', 0)
1769
self.disarm_vehicle(force=True)
1770
self.reboot_sitl()
1771
raise ex
1772
1773
def test_gcs_failsafe(self, side=60, timeout=360):
1774
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
1775
self.set_parameter("FS_ACTION", 1)
1776
self.set_parameter("FS_THR_ENABLE", 0) # disable radio FS as it inhibt GCS one's
1777
1778
def go_somewhere():
1779
self.change_mode("MANUAL")
1780
self.wait_ready_to_arm()
1781
self.arm_vehicle()
1782
self.set_rc(3, 2000)
1783
self.delay_sim_time(5)
1784
self.set_rc(3, 1500)
1785
# Trigger telemetry loss with failsafe disabled. Verify no action taken.
1786
self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action")
1787
self.setGCSfailsafe(0)
1788
go_somewhere()
1789
self.set_heartbeat_rate(0)
1790
self.delay_sim_time(5)
1791
self.wait_mode("MANUAL")
1792
self.set_heartbeat_rate(self.speedup)
1793
self.delay_sim_time(5)
1794
self.wait_mode("MANUAL")
1795
self.end_subtest("Completed GCS failsafe disabled test")
1796
1797
# Trigger telemetry loss with failsafe enabled. Verify
1798
# failsafe triggers to RTL. Restore telemetry, verify failsafe
1799
# clears, and change modes.
1800
# TODO not implemented
1801
# self.start_subtest("GCS failsafe recovery test: FS_GCS_ENABLE=1")
1802
# self.setGCSfailsafe(1)
1803
# self.set_heartbeat_rate(0)
1804
# self.wait_mode("RTL")
1805
# self.set_heartbeat_rate(self.speedup)
1806
# self.wait_statustext("GCS Failsafe Cleared", timeout=60)
1807
# self.change_mode("MANUAL")
1808
# self.end_subtest("Completed GCS failsafe recovery test")
1809
1810
# Trigger telemetry loss with failsafe enabled. Verify failsafe triggers and RTL completes
1811
self.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1")
1812
self.setGCSfailsafe(1)
1813
self.set_heartbeat_rate(0)
1814
self.wait_mode("RTL")
1815
self.wait_statustext("Reached destination", timeout=60)
1816
self.set_heartbeat_rate(self.speedup)
1817
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
1818
self.end_subtest("Completed GCS failsafe RTL")
1819
1820
# Trigger telemetry loss with an invalid failsafe value. Verify failsafe triggers and RTL completes
1821
self.start_subtest("GCS failsafe invalid value with no options test: FS_GCS_ENABLE=99")
1822
self.setGCSfailsafe(99)
1823
go_somewhere()
1824
self.set_heartbeat_rate(0)
1825
self.wait_mode("RTL")
1826
self.wait_statustext("Reached destination", timeout=60)
1827
self.set_heartbeat_rate(self.speedup)
1828
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
1829
self.end_subtest("Completed GCS failsafe invalid value")
1830
1831
self.start_subtest("Testing continue in auto mission")
1832
self.disarm_vehicle()
1833
self.setGCSfailsafe(2)
1834
self.load_mission("test_arming.txt")
1835
self.change_mode("AUTO")
1836
self.delay_sim_time(5)
1837
self.set_heartbeat_rate(0)
1838
self.wait_statustext("Failsafe - Continuing Auto Mode", timeout=60)
1839
self.delay_sim_time(5)
1840
self.wait_mode("AUTO")
1841
self.set_heartbeat_rate(self.speedup)
1842
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
1843
1844
self.start_subtest("GCS failsafe RTL with no options test: FS_GCS_ENABLE=1 and FS_GCS_TIMEOUT=10")
1845
self.setGCSfailsafe(1)
1846
old_gcs_timeout = self.get_parameter("FS_GCS_TIMEOUT")
1847
new_gcs_timeout = old_gcs_timeout * 2
1848
self.set_parameter("FS_GCS_TIMEOUT", new_gcs_timeout)
1849
go_somewhere()
1850
self.set_heartbeat_rate(0)
1851
self.delay_sim_time(old_gcs_timeout + (new_gcs_timeout - old_gcs_timeout) / 2)
1852
self.assert_mode("MANUAL")
1853
self.wait_mode("RTL")
1854
self.wait_statustext("Reached destination", timeout=60)
1855
self.set_heartbeat_rate(self.speedup)
1856
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
1857
self.disarm_vehicle()
1858
self.end_subtest("Completed GCS failsafe RTL")
1859
1860
self.setGCSfailsafe(0)
1861
self.progress("All GCS failsafe tests complete")
1862
1863
def test_gcs_fence_centroid(self, target_system=1, target_component=1):
1864
self.start_subtest("Ensuring if we don't have a centroid it gets calculated")
1865
items = self.test_gcs_fence_need_centroid(
1866
target_system=target_system,
1867
target_component=target_component)
1868
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
1869
items)
1870
centroid = self.get_fence_point(0)
1871
want_lat = 1.0001
1872
want_lng = 1.00005
1873
if abs(centroid.lat - want_lat) > 0.000001:
1874
raise NotAchievedException("Centroid lat not as expected (want=%f got=%f)" % (want_lat, centroid.lat))
1875
if abs(centroid.lng - want_lng) > 0.000001:
1876
raise NotAchievedException("Centroid lng not as expected (want=%f got=%f)" % (want_lng, centroid.lng))
1877
1878
def test_gcs_fence_update_fencepoint(self, target_system=1, target_component=1):
1879
self.start_subtest("Ensuring we can move a fencepoint")
1880
items = self.test_gcs_fence_boring_triangle(
1881
target_system=target_system,
1882
target_component=target_component)
1883
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
1884
items)
1885
# downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1886
item_seq = 2
1887
item = items[item_seq]
1888
print("item is (%s)" % str(item))
1889
self.progress("original x=%d" % item.x)
1890
item.x += int(0.1 * 1e7)
1891
self.progress("new x=%d" % item.x)
1892
self.progress("try to overwrite item %u" % item_seq)
1893
self.mav.mav.mission_write_partial_list_send(
1894
target_system,
1895
target_component,
1896
item_seq,
1897
item_seq,
1898
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1899
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, item_seq)
1900
item.pack(self.mav.mav)
1901
self.mav.mav.send(item)
1902
self.progress("Answered request for fence point %u" % item_seq)
1903
1904
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1905
downloaded_items2 = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
1906
if downloaded_items2[item_seq].x != item.x:
1907
raise NotAchievedException("Item did not update")
1908
self.check_fence_items_same([items[0], items[1], item, items[3]], downloaded_items2)
1909
1910
def test_gcs_fence_boring_triangle(self, target_system=1, target_component=1):
1911
return copy.copy([
1912
self.mav.mav.mission_item_int_encode(
1913
target_system,
1914
target_component,
1915
0, # seq
1916
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1917
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1918
0, # current
1919
0, # autocontinue
1920
3, # p1
1921
0, # p2
1922
0, # p3
1923
0, # p4
1924
int(1.0000 * 1e7), # latitude
1925
int(1.0000 * 1e7), # longitude
1926
31.0000, # altitude
1927
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1928
self.mav.mav.mission_item_int_encode(
1929
target_system,
1930
target_component,
1931
1, # seq
1932
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1933
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1934
0, # current
1935
0, # autocontinue
1936
3, # p1
1937
0, # p2
1938
0, # p3
1939
0, # p4
1940
int(1.0001 * 1e7), # latitude
1941
int(1.0000 * 1e7), # longitude
1942
32.0000, # altitude
1943
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1944
self.mav.mav.mission_item_int_encode(
1945
target_system,
1946
target_component,
1947
2, # seq
1948
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1949
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1950
0, # current
1951
0, # autocontinue
1952
3, # p1
1953
0, # p2
1954
0, # p3
1955
0, # p4
1956
int(1.0001 * 1e7), # latitude
1957
int(1.0001 * 1e7), # longitude
1958
33.0000, # altitude
1959
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1960
self.mav.mav.mission_item_int_encode(
1961
target_system,
1962
target_component,
1963
3, # seq
1964
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1965
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT,
1966
0, # current
1967
0, # autocontinue
1968
0, # p1
1969
0, # p2
1970
0, # p3
1971
0, # p4
1972
int(1.00015 * 1e7), # latitude
1973
int(1.00015 * 1e7), # longitude
1974
33.0000, # altitude
1975
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1976
])
1977
1978
def test_gcs_fence_need_centroid(self, target_system=1, target_component=1):
1979
return copy.copy([
1980
self.mav.mav.mission_item_int_encode(
1981
target_system,
1982
target_component,
1983
0, # seq
1984
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
1985
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
1986
0, # current
1987
0, # autocontinue
1988
4, # p1
1989
0, # p2
1990
0, # p3
1991
0, # p4
1992
int(1.0000 * 1e7), # latitude
1993
int(1.0000 * 1e7), # longitude
1994
31.0000, # altitude
1995
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
1996
self.mav.mav.mission_item_int_encode(
1997
target_system,
1998
target_component,
1999
1, # seq
2000
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
2001
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
2002
0, # current
2003
0, # autocontinue
2004
4, # p1
2005
0, # p2
2006
0, # p3
2007
0, # p4
2008
int(1.0002 * 1e7), # latitude
2009
int(1.0000 * 1e7), # longitude
2010
32.0000, # altitude
2011
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
2012
self.mav.mav.mission_item_int_encode(
2013
target_system,
2014
target_component,
2015
2, # seq
2016
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
2017
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
2018
0, # current
2019
0, # autocontinue
2020
4, # p1
2021
0, # p2
2022
0, # p3
2023
0, # p4
2024
int(1.0002 * 1e7), # latitude
2025
int(1.0001 * 1e7), # longitude
2026
33.0000, # altitude
2027
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
2028
self.mav.mav.mission_item_int_encode(
2029
target_system,
2030
target_component,
2031
3, # seq
2032
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
2033
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
2034
0, # current
2035
0, # autocontinue
2036
4, # p1
2037
0, # p2
2038
0, # p3
2039
0, # p4
2040
int(1.0000 * 1e7), # latitude
2041
int(1.0001 * 1e7), # longitude
2042
33.0000, # altitude
2043
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
2044
])
2045
2046
def click_location_from_item(self, mavproxy, item):
2047
mavproxy.send("click %f %f\n" % (item.x*1e-7, item.y*1e-7))
2048
2049
def test_gcs_fence_via_mavproxy(self, target_system=1, target_component=1):
2050
self.start_subtest("Fence via MAVProxy")
2051
if not self.mavproxy_can_do_mision_item_protocols():
2052
return
2053
mavproxy = self.start_mavproxy()
2054
self.start_subsubtest("fence addcircle")
2055
self.clear_fence_using_mavproxy(mavproxy)
2056
self.delay_sim_time(1)
2057
radius = 20
2058
item = self.mav.mav.mission_item_int_encode(
2059
target_system,
2060
target_component,
2061
0, # seq
2062
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
2063
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
2064
0, # current
2065
0, # autocontinue
2066
radius, # p1
2067
0, # p2
2068
0, # p3
2069
0, # p4
2070
int(1.0017 * 1e7), # latitude
2071
int(1.0017 * 1e7), # longitude
2072
0.0000, # altitude
2073
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2074
print("item is (%s)" % str(item))
2075
self.click_location_from_item(mavproxy, item)
2076
mavproxy.send("fence addcircle inc %u\n" % radius)
2077
self.delay_sim_time(1)
2078
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2079
print("downloaded items: %s" % str(downloaded_items))
2080
self.check_fence_items_same([item], downloaded_items)
2081
2082
radius_exc = 57.3
2083
item2 = self.mav.mav.mission_item_int_encode(
2084
target_system,
2085
target_component,
2086
0, # seq
2087
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
2088
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
2089
0, # current
2090
0, # autocontinue
2091
radius_exc, # p1
2092
0, # p2
2093
0, # p3
2094
0, # p4
2095
int(1.0017 * 1e7), # latitude
2096
int(1.0017 * 1e7), # longitude
2097
0.0000, # altitude
2098
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2099
self.click_location_from_item(mavproxy, item2)
2100
mavproxy.send("fence addcircle exc %f\n" % radius_exc)
2101
self.delay_sim_time(1)
2102
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2103
print("downloaded items: %s" % str(downloaded_items))
2104
self.check_fence_items_same([item, item2], downloaded_items)
2105
self.end_subsubtest("fence addcircle")
2106
2107
self.start_subsubtest("fence addpoly")
2108
self.clear_fence_using_mavproxy(mavproxy)
2109
self.delay_sim_time(1)
2110
pointcount = 7
2111
mavproxy.send("fence addpoly inc 20 %u 37.2\n" % pointcount) # radius, pointcount, rotaiton
2112
self.delay_sim_time(5)
2113
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2114
if len(downloaded_items) != pointcount:
2115
raise NotAchievedException("Did not get expected number of points returned (want=%u got=%u)" %
2116
(pointcount, len(downloaded_items)))
2117
self.end_subsubtest("fence addpoly")
2118
2119
self.start_subsubtest("fence movepolypoint")
2120
self.clear_fence_using_mavproxy(mavproxy)
2121
self.delay_sim_time(1)
2122
triangle = self.test_gcs_fence_boring_triangle(
2123
target_system=target_system,
2124
target_component=target_component)
2125
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
2126
triangle)
2127
mavproxy.send("fence list\n")
2128
self.delay_sim_time(1)
2129
triangle[2].x += 500
2130
triangle[2].y += 700
2131
self.click_location_from_item(mavproxy, triangle[2])
2132
mavproxy.send("fence movepolypoint 0 2\n")
2133
self.delay_sim_time(10)
2134
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2135
self.check_fence_items_same(triangle, downloaded_items)
2136
self.end_subsubtest("fence movepolypoint")
2137
2138
self.start_subsubtest("fence enable and disable")
2139
mavproxy.send("fence enable\n")
2140
mavproxy.expect("fence enabled")
2141
mavproxy.send("fence disable\n")
2142
mavproxy.expect("fence disabled")
2143
self.end_subsubtest("fence enable and disable")
2144
2145
self.stop_mavproxy(mavproxy)
2146
2147
# MANUAL> usage: fence <addcircle|addpoly|changealt|clear|disable|draw|enable|list|load|move|movemulti|movepolypoint|param|remove|save|savecsv|savelocal|show|status|undo|update> # noqa
2148
2149
def GCSFence(self):
2150
'''Upload and download of fence'''
2151
target_system = 1
2152
target_component = 1
2153
2154
self.progress("Testing FENCE_POINT protocol")
2155
2156
self.start_subtest("FENCE_TOTAL manipulation")
2157
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2158
self.assert_parameter_value("FENCE_TOTAL", 0)
2159
2160
self.set_parameter("FENCE_TOTAL", 5)
2161
self.assert_parameter_value("FENCE_TOTAL", 5)
2162
2163
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2164
self.assert_parameter_value("FENCE_TOTAL", 0)
2165
2166
self.progress("sending out-of-range fencepoint")
2167
self.send_fencepoint_expect_statustext(0,
2168
0,
2169
1.2345,
2170
5.4321,
2171
"index past total",
2172
target_system=target_component,
2173
target_component=target_component)
2174
2175
self.progress("sending another out-of-range fencepoint")
2176
self.send_fencepoint_expect_statustext(0,
2177
1,
2178
1.2345,
2179
5.4321,
2180
"bad count",
2181
target_system=target_component,
2182
target_component=target_component)
2183
2184
self.set_parameter("FENCE_TOTAL", 1)
2185
self.assert_parameter_value("FENCE_TOTAL", 1)
2186
2187
self.send_fencepoint_expect_statustext(0,
2188
1,
2189
1.2345,
2190
5.4321,
2191
"Invalid FENCE_TOTAL",
2192
target_system=target_component,
2193
target_component=target_component)
2194
2195
self.set_parameter("FENCE_TOTAL", 5)
2196
self.progress("Checking default points")
2197
for i in range(5):
2198
m = self.get_fence_point(i)
2199
if m.count != 5:
2200
raise NotAchievedException("Unexpected count in fence point (want=%u got=%u" %
2201
(5, m.count))
2202
if m.lat != 0 or m.lng != 0:
2203
raise NotAchievedException("Unexpected lat/lon in fencepoint")
2204
2205
self.progress("Storing a return point")
2206
self.roundtrip_fencepoint_protocol(0,
2207
5,
2208
1.2345,
2209
5.4321,
2210
target_system=target_system,
2211
target_component=target_component)
2212
2213
lat = 2.345
2214
lng = 4.321
2215
self.roundtrip_fencepoint_protocol(0,
2216
5,
2217
lat,
2218
lng,
2219
target_system=target_system,
2220
target_component=target_component)
2221
2222
if not self.mavproxy_can_do_mision_item_protocols():
2223
self.progress("MAVProxy too old to do fence point protocols")
2224
return
2225
2226
self.progress("Download with new protocol")
2227
items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2228
if len(items) != 1:
2229
raise NotAchievedException("Unexpected fencepoint count (want=%u got=%u)" % (1, len(items)))
2230
if items[0].command != mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT:
2231
raise NotAchievedException(
2232
"Fence return point not of correct type expected (%u) got %u" %
2233
(items[0].command,
2234
mavutil.mavlink.MAV_CMD_NAV_FENCE_RETURN_POINT))
2235
if items[0].frame != mavutil.mavlink.MAV_FRAME_GLOBAL:
2236
raise NotAchievedException(
2237
"Unexpected frame want=%s got=%s," %
2238
(self.string_for_frame(mavutil.mavlink.MAV_FRAME_GLOBAL),
2239
self.string_for_frame(items[0].frame)))
2240
got_lat = items[0].x
2241
want_lat = lat * 1e7
2242
if abs(got_lat - want_lat) > 1:
2243
raise NotAchievedException("Disagree in lat (got=%f want=%f)" % (got_lat, want_lat))
2244
if abs(items[0].y - lng * 1e7) > 1:
2245
raise NotAchievedException("Disagree in lng")
2246
if items[0].seq != 0:
2247
raise NotAchievedException("Disagree in offset")
2248
self.progress("Downloaded with new protocol OK")
2249
2250
# upload using mission protocol:
2251
items = self.test_gcs_fence_boring_triangle(
2252
target_system=target_system,
2253
target_component=target_component)
2254
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
2255
items)
2256
2257
self.progress("Download with new protocol")
2258
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2259
if len(downloaded_items) != len(items):
2260
raise NotAchievedException("Did not download expected number of items (wanted=%u got=%u)" %
2261
(len(items), len(downloaded_items)))
2262
self.assert_parameter_value("FENCE_TOTAL", len(items) + 1) # +1 for closing
2263
self.progress("Ensuring fence items match what we sent up")
2264
self.check_fence_items_same(items, downloaded_items)
2265
2266
# now check centroid
2267
self.progress("Requesting fence return point")
2268
self.mav.mav.fence_fetch_point_send(target_system,
2269
target_component,
2270
0)
2271
m = self.mav.recv_match(type="FENCE_POINT", blocking=True, timeout=1)
2272
print("m: %s" % str(m))
2273
2274
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
2275
target_system=target_system,
2276
target_component=target_component)
2277
self.progress("Checking count post-nuke")
2278
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
2279
target_system=target_system,
2280
target_component=target_component)
2281
self.assert_mission_count_on_link(self.mav,
2282
0,
2283
target_system,
2284
target_component,
2285
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
2286
2287
self.start_subtest("Ensuring bad fences get bounced")
2288
for fence in self.fences_which_should_not_upload(target_system=target_system, target_component=target_component):
2289
(name, items) = fence
2290
self.progress("Ensuring (%s) gets bounced" % (name,))
2291
self.assert_fence_does_not_upload(items)
2292
2293
self.start_subtest("Ensuring good fences don't get bounced")
2294
for fence in self.fences_which_should_upload(target_system=target_system, target_component=target_component):
2295
(name, items) = fence
2296
self.progress("Ensuring (%s) gets uploaded" % (name,))
2297
self.check_fence_upload_download(items)
2298
self.progress("(%s) uploaded just fine" % (name,))
2299
2300
self.test_gcs_fence_update_fencepoint(target_system=target_system,
2301
target_component=target_component)
2302
2303
self.test_gcs_fence_centroid(target_system=target_system,
2304
target_component=target_component)
2305
2306
self.test_gcs_fence_via_mavproxy(target_system=target_system,
2307
target_component=target_component)
2308
2309
# explode the write_type_to_storage method
2310
# FIXME: test converting invalid fences / minimally valid fences / normal fences
2311
# FIXME: show that uploading smaller items take up less space
2312
# FIXME: add test for consecutive breaches within the manual recovery period
2313
# FIXME: ensure truncation does the right thing by fence_total
2314
2315
# FIXME: test vehicle escape from outside inclusion zones to
2316
# inside inclusion zones (and inside exclusion zones to outside
2317
# exclusion zones)
2318
# FIXME: add test that a fence with edges that cross can't be uploaded
2319
# FIXME: add a test that fences enclose an area (e.g. all the points aren't the same value!
2320
def Offboard(self, timeout=90):
2321
'''Test Offboard Control'''
2322
self.load_mission("rover-guided-mission.txt")
2323
self.wait_ready_to_arm(require_absolute=True)
2324
self.arm_vehicle()
2325
self.change_mode("AUTO")
2326
2327
offboard_expected_duration = 10 # see mission file
2328
2329
if self.mav.messages.get("SET_POSITION_TARGET_GLOBAL_INT", None):
2330
raise PreconditionFailedException("Already have SET_POSITION_TARGET_GLOBAL_INT")
2331
2332
tstart = self.get_sim_time_cached()
2333
last_heartbeat_sent = 0
2334
got_ptgi = False
2335
magic_waypoint_tstart = 0
2336
magic_waypoint_tstop = 0
2337
while True:
2338
now = self.get_sim_time_cached()
2339
if now - last_heartbeat_sent > 1:
2340
last_heartbeat_sent = now
2341
self.mav.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
2342
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
2343
0,
2344
0,
2345
0)
2346
2347
if now - tstart > timeout:
2348
raise AutoTestTimeoutException("Didn't complete")
2349
magic_waypoint = 3
2350
mc = self.mav.recv_match(type=["MISSION_CURRENT", "STATUSTEXT"],
2351
blocking=False)
2352
if mc is not None:
2353
print("%s" % str(mc))
2354
if mc.get_type() == "STATUSTEXT":
2355
if "Mission Complete" in mc.text:
2356
break
2357
continue
2358
if mc.seq == magic_waypoint:
2359
print("At magic waypoint")
2360
if magic_waypoint_tstart == 0:
2361
magic_waypoint_tstart = self.get_sim_time_cached()
2362
ptgi = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None)
2363
if ptgi is not None:
2364
got_ptgi = True
2365
elif mc.seq > magic_waypoint:
2366
if magic_waypoint_tstop == 0:
2367
magic_waypoint_tstop = self.get_sim_time_cached()
2368
2369
self.disarm_vehicle()
2370
offboard_duration = magic_waypoint_tstop - magic_waypoint_tstart
2371
if abs(offboard_duration - offboard_expected_duration) > 1:
2372
raise NotAchievedException("Did not stay in offboard control for correct time (want=%f got=%f)" %
2373
(offboard_expected_duration, offboard_duration))
2374
2375
if not got_ptgi:
2376
raise NotAchievedException("Did not get ptgi message")
2377
print("pgti: %s" % str(ptgi))
2378
2379
def assert_mission_count_on_link(self, mav, expected_count, target_system, target_component, mission_type):
2380
self.drain_mav_unparsed(mav=mav, freshen_sim_time=True)
2381
self.progress("waiting for a message - any message....")
2382
m = mav.recv_match(blocking=True, timeout=1)
2383
self.progress("Received (%s)" % str(m))
2384
2385
if not mav.mavlink20():
2386
raise NotAchievedException("Not doing mavlink2")
2387
mav.mav.mission_request_list_send(target_system,
2388
target_component,
2389
mission_type)
2390
self.assert_receive_mission_count_on_link(mav,
2391
expected_count,
2392
target_system,
2393
target_component,
2394
mission_type)
2395
2396
def assert_receive_mission_count_on_link(self,
2397
mav,
2398
expected_count,
2399
target_system,
2400
target_component,
2401
mission_type,
2402
expected_target_system=None,
2403
expected_target_component=None,
2404
timeout=120):
2405
if expected_target_system is None:
2406
expected_target_system = mav.mav.srcSystem
2407
if expected_target_component is None:
2408
expected_target_component = mav.mav.srcComponent
2409
self.progress("Waiting for mission count of (%u) from (%u:%u) to (%u:%u)" %
2410
(expected_count, target_system, target_component, expected_target_system, expected_target_component))
2411
2412
tstart = self.get_sim_time_cached()
2413
while True:
2414
delta = self.get_sim_time_cached() - tstart
2415
if delta > timeout:
2416
raise NotAchievedException("Did not receive MISSION_COUNT on link after %fs" % delta)
2417
m = mav.recv_match(blocking=True, timeout=1)
2418
if m is None:
2419
self.progress("No messages")
2420
continue
2421
# self.progress("Received (%s)" % str(m))
2422
if m.get_type() == "MISSION_ACK":
2423
if m.type != mavutil.mavlink.MAV_MISSION_ACCEPTED:
2424
raise NotAchievedException("Expected MAV_MISSION_ACCEPTED, got (%s)" % m)
2425
if m.get_type() == "MISSION_COUNT":
2426
break
2427
if m.target_system != expected_target_system:
2428
raise NotAchievedException("Incorrect target system in MISSION_COUNT (want=%u got=%u)" %
2429
(expected_target_system, m.target_system))
2430
if m.target_component != expected_target_component:
2431
raise NotAchievedException("Incorrect target component in MISSION_COUNT")
2432
if m.mission_type != mission_type:
2433
raise NotAchievedException("Did not get expected mission type (want=%u got=%u)" % (mission_type, m.mission_type))
2434
if m.count != expected_count:
2435
raise NotAchievedException("Bad count received (want=%u got=%u)" %
2436
(expected_count, m.count))
2437
self.progress("Asserted mission count (type=%u) is %u after %fs" % (
2438
(mission_type, m.count, delta)))
2439
2440
def get_mission_item_int_on_link(self, item, mav, target_system, target_component, mission_type, delay_fn=None):
2441
self.drain_mav(mav=mav, unparsed=True)
2442
mav.mav.mission_request_int_send(target_system,
2443
target_component,
2444
item,
2445
mission_type)
2446
m = self.assert_receive_message(
2447
'MISSION_ITEM_INT',
2448
timeout=60,
2449
condition='MISSION_ITEM_INT.mission_type==%u' % mission_type,
2450
delay_fn=delay_fn)
2451
if m is None:
2452
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
2453
if m.mission_type != mission_type:
2454
raise NotAchievedException("Mission item of incorrect type")
2455
if m.target_system != mav.mav.srcSystem:
2456
raise NotAchievedException("Unexpected target system %u want=%u" %
2457
(m.target_system, mav.mav.srcSystem))
2458
if m.seq != item:
2459
raise NotAchievedException(
2460
"Incorrect sequence number on received item got=%u want=%u" %
2461
(m.seq, item))
2462
if m.mission_type != mission_type:
2463
raise NotAchievedException(
2464
"Mission type incorrect on received item (want=%u got=%u)" %
2465
(mission_type, m.mission_type))
2466
if m.target_component != mav.mav.srcComponent:
2467
raise NotAchievedException(
2468
"Unexpected target component %u want=%u" %
2469
(m.target_component, mav.mav.srcComponent))
2470
return m
2471
2472
def get_mission_item_on_link(self, item, mav, target_system, target_component, mission_type):
2473
self.drain_mav(mav=mav, unparsed=True)
2474
mav.mav.mission_request_send(target_system,
2475
target_component,
2476
item,
2477
mission_type)
2478
m = mav.recv_match(type='MISSION_ITEM',
2479
blocking=True,
2480
timeout=60)
2481
if m is None:
2482
raise NotAchievedException("Did not receive MISSION_ITEM")
2483
if m.target_system != mav.mav.srcSystem:
2484
raise NotAchievedException("Unexpected target system %u want=%u" %
2485
(m.target_system, mav.mav.srcSystem))
2486
if m.seq != item:
2487
raise NotAchievedException("Incorrect sequence number on received item_int got=%u want=%u" %
2488
(m.seq, item))
2489
if m.mission_type != mission_type:
2490
raise NotAchievedException("Mission type incorrect on received item_int (want=%u got=%u)" %
2491
(mission_type, m.mission_type))
2492
if m.target_component != mav.mav.srcComponent:
2493
raise NotAchievedException("Unexpected target component %u want=%u" %
2494
(m.target_component, mav.mav.srcComponent))
2495
return m
2496
2497
def assert_receive_mission_item_request(self, mission_type, seq):
2498
self.progress("Expecting request for item %u" % seq)
2499
m = self.assert_receive_message('MISSION_REQUEST', timeout=1)
2500
if m.mission_type != mission_type:
2501
raise NotAchievedException("Incorrect mission type (wanted=%u got=%u)" %
2502
(mission_type, m.mission_type))
2503
if m.seq != seq:
2504
raise NotAchievedException("Unexpected sequence number (want=%u got=%u)" % (seq, m.seq))
2505
self.progress("Received item request OK")
2506
2507
def assert_receive_mission_ack(self, mission_type,
2508
want_type=mavutil.mavlink.MAV_MISSION_ACCEPTED,
2509
target_system=None,
2510
target_component=None,
2511
mav=None):
2512
if mav is None:
2513
mav = self.mav
2514
if target_system is None:
2515
target_system = mav.mav.srcSystem
2516
if target_component is None:
2517
target_component = mav.mav.srcComponent
2518
self.progress("Expecting mission ack")
2519
m = mav.recv_match(type='MISSION_ACK',
2520
blocking=True,
2521
timeout=5)
2522
self.progress("Received ACK (%s)" % str(m))
2523
if m is None:
2524
raise NotAchievedException("Expected mission ACK")
2525
if m.target_system != target_system:
2526
raise NotAchievedException("ACK not targetted at correct system want=%u got=%u" %
2527
(target_system, m.target_system))
2528
if m.target_component != target_component:
2529
raise NotAchievedException("ACK not targetted at correct component")
2530
if m.mission_type != mission_type:
2531
raise NotAchievedException("Unexpected mission type %u want=%u" %
2532
(m.mission_type, mission_type))
2533
if m.type != want_type:
2534
raise NotAchievedException("Expected ack type %u got %u" %
2535
(want_type, m.type))
2536
2537
def assert_filepath_content(self, filepath, want):
2538
with open(filepath) as f:
2539
got = f.read()
2540
if want != got:
2541
raise NotAchievedException("Did not get expected file content (want=%s) (got=%s)" % (want, got))
2542
2543
def mavproxy_can_do_mision_item_protocols(self):
2544
return False
2545
if not self.mavproxy_version_gt(1, 8, 69):
2546
self.progress("MAVProxy is too old; skipping tests")
2547
return False
2548
return True
2549
2550
def check_rally_items_same(self, want, got, epsilon=None):
2551
check_atts = ['mission_type', 'command', 'x', 'y', 'z', 'seq', 'param1']
2552
return self.check_mission_items_same(check_atts, want, got, epsilon=epsilon)
2553
2554
def click_three_in(self, mavproxy, target_system=1, target_component=1):
2555
mavproxy.send('rally clear\n')
2556
self.drain_mav()
2557
# there are race conditions in MAVProxy. Beware.
2558
mavproxy.send("click 1.0 1.0\n")
2559
mavproxy.send("rally add\n")
2560
self.delay_sim_time(1)
2561
mavproxy.send("click 2.0 2.0\n")
2562
mavproxy.send("rally add\n")
2563
self.delay_sim_time(1)
2564
mavproxy.send("click 3.0 3.0\n")
2565
mavproxy.send("rally add\n")
2566
self.delay_sim_time(10)
2567
self.assert_mission_count_on_link(
2568
self.mav,
2569
3,
2570
target_system,
2571
target_component,
2572
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2573
)
2574
2575
def GCSRally(self, target_system=1, target_component=1):
2576
'''Upload and download of rally using MAVProxy'''
2577
self.start_subtest("Testing mavproxy CLI for rally points")
2578
if not self.mavproxy_can_do_mision_item_protocols():
2579
return
2580
2581
mavproxy = self.start_mavproxy()
2582
2583
mavproxy.send('rally clear\n')
2584
2585
self.start_subsubtest("rally add")
2586
mavproxy.send('rally clear\n')
2587
lat_s = "-5.6789"
2588
lng_s = "98.2341"
2589
lat = float(lat_s)
2590
lng = float(lng_s)
2591
mavproxy.send('click %s %s\n' % (lat_s, lng_s))
2592
self.drain_mav()
2593
mavproxy.send('rally add\n')
2594
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2595
target_system=255,
2596
target_component=0)
2597
self.delay_sim_time(5)
2598
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2599
if len(downloaded_items) != 1:
2600
raise NotAchievedException("Unexpected count (got=%u want=1)" %
2601
(len(downloaded_items), ))
2602
if (downloaded_items[0].x - int(lat * 1e7)) > 1:
2603
raise NotAchievedException("Bad rally lat. Want=%d got=%d" %
2604
(int(lat * 1e7), downloaded_items[0].x))
2605
if (downloaded_items[0].y - int(lng * 1e7)) > 1:
2606
raise NotAchievedException("Bad rally lng. Want=%d got=%d" %
2607
(int(lng * 1e7), downloaded_items[0].y))
2608
if (downloaded_items[0].z - int(90)) > 1:
2609
raise NotAchievedException("Bad rally alt. Want=90 got=%d" %
2610
(downloaded_items[0].y))
2611
self.end_subsubtest("rally add")
2612
2613
self.start_subsubtest("rally list")
2614
util.pexpect_drain(mavproxy)
2615
mavproxy.send('rally list\n')
2616
mavproxy.expect(r"Saved 1 rally items to ([^\s]*)\s")
2617
filename = mavproxy.match.group(1)
2618
self.assert_rally_filepath_content(filename, '''QGC WPL 110
2619
0 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 0
2620
''')
2621
self.end_subsubtest("rally list")
2622
2623
self.start_subsubtest("rally save")
2624
util.pexpect_drain(mavproxy)
2625
save_tmppath = self.buildlogs_path("rally-testing-tmp.txt")
2626
mavproxy.send('rally save %s\n' % save_tmppath)
2627
mavproxy.expect(r"Saved 1 rally items to ([^\s]*)\s")
2628
filename = mavproxy.match.group(1)
2629
if filename != save_tmppath:
2630
raise NotAchievedException("Bad save filepath; want=%s got=%s" % (save_tmppath, filename))
2631
self.assert_rally_filepath_content(filename, '''QGC WPL 110
2632
0 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 0
2633
''')
2634
self.end_subsubtest("rally save")
2635
2636
self.start_subsubtest("rally savecsv")
2637
util.pexpect_drain(mavproxy)
2638
csvpath = self.buildlogs_path("rally-testing-tmp.csv")
2639
mavproxy.send('rally savecsv %s\n' % csvpath)
2640
mavproxy.expect('"Seq","Frame"')
2641
expected_content = '''"Seq","Frame","Cmd","P1","P2","P3","P4","X","Y","Z"
2642
"0","Rel","NAV_RALLY_POINT","0.0","0.0","0.0","0.0","-5.67890024185","98.2341003418","90.0"
2643
'''
2644
if sys.version_info[0] >= 3:
2645
# greater precision output by default
2646
expected_content = '''"Seq","Frame","Cmd","P1","P2","P3","P4","X","Y","Z"
2647
"0","Rel","NAV_RALLY_POINT","0.0","0.0","0.0","0.0","-5.678900241851807","98.23410034179688","90.0"
2648
'''
2649
self.assert_filepath_content(csvpath, expected_content)
2650
2651
self.end_subsubtest("rally savecsv")
2652
2653
self.start_subsubtest("rally load")
2654
self.drain_mav()
2655
mavproxy.send('rally clear\n')
2656
self.assert_mission_count_on_link(self.mav,
2657
0,
2658
target_system,
2659
target_component,
2660
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2661
2662
# warning: uses file saved from previous test
2663
self.start_subtest("Check rally load from filepath")
2664
mavproxy.send('rally load %s\n' % save_tmppath)
2665
mavproxy.expect(r"Loaded 1 rally items from ([^\s]*)\s")
2666
mavproxy.expect("Sent all .* rally items") # notional race condition here
2667
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2668
if len(downloaded_items) != 1:
2669
raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))
2670
if abs(int(downloaded_items[0].x) - int(lat * 1e7)) > 3:
2671
raise NotAchievedException("Expected lat=%d got=%d" %
2672
(lat * 1e7, downloaded_items[0].x))
2673
if abs(int(downloaded_items[0].y) - int(lng * 1e7)) > 10:
2674
raise NotAchievedException("Expected lng=%d got=%d" %
2675
(lng * 1e7, downloaded_items[0].y))
2676
self.end_subsubtest("rally load")
2677
2678
self.start_subsubtest("rally changealt")
2679
mavproxy.send('rally clear\n')
2680
mavproxy.send("click 1.0 1.0\n")
2681
mavproxy.send("rally add\n")
2682
mavproxy.send("click 2.0 2.0\n")
2683
mavproxy.send("rally add\n")
2684
self.delay_sim_time(10)
2685
self.assert_mission_count_on_link(
2686
self.mav,
2687
2,
2688
target_system,
2689
target_component,
2690
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2691
)
2692
self.drain_mav()
2693
mavproxy.send("rally changealt 1 17.6\n")
2694
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2695
target_system=255,
2696
target_component=0)
2697
self.delay_sim_time(10)
2698
mavproxy.send("rally changealt 2 19.1\n")
2699
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2700
target_system=255,
2701
target_component=0)
2702
self.delay_sim_time(10)
2703
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2704
if len(downloaded_items) != 2:
2705
raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))
2706
if abs(int(downloaded_items[0].x) - int(1 * 1e7)) > 3:
2707
raise NotAchievedException("Expected lat=%d got=%d" % (1 * 1e7, downloaded_items[0].x))
2708
if abs(int(downloaded_items[0].y) - int(1 * 1e7)) > 10:
2709
raise NotAchievedException("Expected lng=%d got=%d" % (1 * 1e7, downloaded_items[0].y))
2710
# at some stage ArduPilot will stop rounding altitude. This
2711
# will break then.
2712
if abs(int(downloaded_items[0].z) - int(17.6)) > 0.0001:
2713
raise NotAchievedException("Expected alt=%f got=%f" % (17.6, downloaded_items[0].z))
2714
2715
if abs(int(downloaded_items[1].x) - int(2 * 1e7)) > 3:
2716
raise NotAchievedException("Expected lat=%d got=%d" % (2 * 1e7, downloaded_items[0].x))
2717
if abs(int(downloaded_items[1].y) - int(2 * 1e7)) > 10:
2718
raise NotAchievedException("Expected lng=%d got=%d" % (2 * 1e7, downloaded_items[0].y))
2719
# at some stage ArduPilot will stop rounding altitude. This
2720
# will break then.
2721
if abs(int(downloaded_items[1].z) - int(19.1)) > 0.0001:
2722
raise NotAchievedException("Expected alt=%f got=%f" % (19.1, downloaded_items[1].z))
2723
2724
self.progress("Now change two at once")
2725
mavproxy.send("rally changealt 1 17.3 2\n")
2726
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2727
target_system=255,
2728
target_component=0)
2729
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2730
if len(downloaded_items) != 2:
2731
raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))
2732
2733
if abs(int(downloaded_items[0].x) - int(1 * 1e7)) > 3:
2734
raise NotAchievedException("Expected lat=%d got=%d" % (1 * 1e7, downloaded_items[0].x))
2735
if abs(int(downloaded_items[0].y) - int(1 * 1e7)) > 10:
2736
raise NotAchievedException("Expected lng=%d got=%d" % (1 * 1e7, downloaded_items[0].y))
2737
# at some stage ArduPilot will stop rounding altitude. This
2738
# will break then.
2739
if abs(int(downloaded_items[0].z) - int(17.3)) > 0.0001:
2740
raise NotAchievedException("Expected alt=%f got=%f" % (17.3, downloaded_items[0].z))
2741
2742
if abs(int(downloaded_items[1].x) - int(2 * 1e7)) > 3:
2743
raise NotAchievedException("Expected lat=%d got=%d" % (2 * 1e7, downloaded_items[0].x))
2744
if abs(int(downloaded_items[1].y) - int(2 * 1e7)) > 10:
2745
raise NotAchievedException("Expected lng=%d got=%d" % (2 * 1e7, downloaded_items[0].y))
2746
# at some stage ArduPilot will stop rounding altitude. This
2747
# will break then.
2748
if abs(int(downloaded_items[1].z) - int(17.3)) > 0.0001:
2749
raise NotAchievedException("Expected alt=%f got=%f" % (17.3, downloaded_items[0].z))
2750
2751
self.end_subsubtest("rally changealt")
2752
2753
self.start_subsubtest("rally move")
2754
mavproxy.send('rally clear\n')
2755
mavproxy.send("click 1.0 1.0\n")
2756
mavproxy.send("rally add\n")
2757
mavproxy.send("click 2.0 2.0\n")
2758
mavproxy.send("rally add\n")
2759
self.delay_sim_time(5)
2760
self.assert_mission_count_on_link(
2761
self.mav,
2762
2,
2763
target_system,
2764
target_component,
2765
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2766
)
2767
mavproxy.send("click 3.0 3.0\n")
2768
mavproxy.send("rally move 2\n")
2769
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2770
target_system=255,
2771
target_component=0)
2772
mavproxy.send("click 4.12345 4.987654\n")
2773
mavproxy.send("rally move 1\n")
2774
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2775
target_system=255,
2776
target_component=0)
2777
2778
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2779
if len(downloaded_items) != 2:
2780
raise NotAchievedException("Unexpected item count (%u)" % len(downloaded_items))
2781
if downloaded_items[0].x != 41234500:
2782
raise NotAchievedException("Bad latitude")
2783
if downloaded_items[0].y != 49876540:
2784
raise NotAchievedException("Bad longitude")
2785
if downloaded_items[0].z != 90:
2786
raise NotAchievedException("Bad altitude (want=%u got=%u)" %
2787
(90, downloaded_items[0].z))
2788
2789
if downloaded_items[1].x != 30000000:
2790
raise NotAchievedException("Bad latitude")
2791
if downloaded_items[1].y != 30000000:
2792
raise NotAchievedException("Bad longitude")
2793
if downloaded_items[1].z != 90:
2794
raise NotAchievedException("Bad altitude (want=%u got=%u)" %
2795
(90, downloaded_items[1].z))
2796
self.end_subsubtest("rally move")
2797
2798
self.start_subsubtest("rally movemulti")
2799
self.drain_mav()
2800
mavproxy.send('rally clear\n')
2801
self.drain_mav()
2802
# there are race conditions in MAVProxy. Beware.
2803
mavproxy.send("click 1.0 1.0\n")
2804
mavproxy.send("rally add\n")
2805
mavproxy.send("click 2.0 2.0\n")
2806
mavproxy.send("rally add\n")
2807
mavproxy.send("click 3.0 3.0\n")
2808
mavproxy.send("rally add\n")
2809
self.delay_sim_time(10)
2810
self.assert_mission_count_on_link(
2811
self.mav,
2812
3,
2813
target_system,
2814
target_component,
2815
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2816
)
2817
click_lat = 2.0
2818
click_lon = 3.0
2819
unmoved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2820
if len(unmoved_items) != 3:
2821
raise NotAchievedException("Unexpected item count")
2822
mavproxy.send("click %f %f\n" % (click_lat, click_lon))
2823
mavproxy.send("rally movemulti 2 1 3\n")
2824
# MAVProxy currently sends three separate items up. That's
2825
# not great and I don't want to lock that behaviour in here.
2826
self.delay_sim_time(10)
2827
expected_moved_items = copy.copy(unmoved_items)
2828
expected_moved_items[0].x = 1.0 * 1e7
2829
expected_moved_items[0].y = 2.0 * 1e7
2830
expected_moved_items[1].x = 2.0 * 1e7
2831
expected_moved_items[1].y = 3.0 * 1e7
2832
expected_moved_items[2].x = 3.0 * 1e7
2833
expected_moved_items[2].y = 4.0 * 1e7
2834
moved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2835
# we're moving an entire degree in latitude; quite an epsilon required...
2836
self.check_rally_items_same(expected_moved_items, moved_items, epsilon=10000)
2837
2838
self.progress("now move back and rotate through 90 degrees")
2839
mavproxy.send("click %f %f\n" % (2, 2))
2840
mavproxy.send("rally movemulti 2 1 3 90\n")
2841
2842
# MAVProxy currently sends three separate items up. That's
2843
# not great and I don't want to lock that behaviour in here.
2844
self.delay_sim_time(10)
2845
expected_moved_items = copy.copy(unmoved_items)
2846
expected_moved_items[0].x = 3.0 * 1e7
2847
expected_moved_items[0].y = 1.0 * 1e7
2848
expected_moved_items[1].x = 2.0 * 1e7
2849
expected_moved_items[1].y = 2.0 * 1e7
2850
expected_moved_items[2].x = 1.0 * 1e7
2851
expected_moved_items[2].y = 3.0 * 1e7
2852
moved_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2853
# we're moving an entire degree in latitude; quite an epsilon required...
2854
self.check_rally_items_same(expected_moved_items, moved_items, epsilon=12000)
2855
self.end_subsubtest("rally movemulti")
2856
2857
self.start_subsubtest("rally param")
2858
mavproxy.send("rally param 3 2 5\n")
2859
mavproxy.expect("Set param 2 for 3 to 5.000000")
2860
self.end_subsubtest("rally param")
2861
2862
self.start_subsubtest("rally remove")
2863
self.click_three_in(target_system=target_system, target_component=target_component)
2864
pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2865
self.progress("Removing last in list")
2866
mavproxy.send("rally remove 3\n")
2867
self.delay_sim_time(10)
2868
self.assert_mission_count_on_link(
2869
self.mav,
2870
2,
2871
target_system,
2872
target_component,
2873
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2874
)
2875
fewer_downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2876
if len(fewer_downloaded_items) != 2:
2877
raise NotAchievedException("Unexpected download list length")
2878
shorter_items = copy.copy(pure_items)
2879
shorter_items = shorter_items[0:2]
2880
self.check_rally_items_same(shorter_items, fewer_downloaded_items)
2881
2882
self.progress("Removing first in list")
2883
mavproxy.send("rally remove 1\n")
2884
self.delay_sim_time(5)
2885
self.assert_mission_count_on_link(
2886
self.mav,
2887
1,
2888
target_system,
2889
target_component,
2890
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2891
)
2892
fewer_downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2893
if len(fewer_downloaded_items) != 1:
2894
raise NotAchievedException("Unexpected download list length")
2895
shorter_items = shorter_items[1:]
2896
self.check_rally_items_same(shorter_items, fewer_downloaded_items)
2897
2898
self.progress("Removing remaining item")
2899
mavproxy.send("rally remove 1\n")
2900
self.delay_sim_time(5)
2901
self.assert_mission_count_on_link(
2902
self.mav,
2903
0,
2904
target_system,
2905
target_component,
2906
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2907
)
2908
self.end_subsubtest("rally remove")
2909
2910
self.start_subsubtest("rally show")
2911
# what can we test here?
2912
mavproxy.send("rally show %s\n" % save_tmppath)
2913
self.end_subsubtest("rally show")
2914
2915
# savelocal must be run immediately after show!
2916
self.start_subsubtest("rally savelocal")
2917
util.pexpect_drain(mavproxy)
2918
savelocal_path = self.buildlogs_path("rally-testing-tmp-local.txt")
2919
mavproxy.send('rally savelocal %s\n' % savelocal_path)
2920
self.delay_sim_time(5)
2921
self.assert_rally_filepath_content(savelocal_path, '''QGC WPL 110
2922
0 0 3 5100 0.000000 0.000000 0.000000 0.000000 -5.678900 98.234100 90.000000 0
2923
''')
2924
self.end_subsubtest("rally savelocal")
2925
2926
self.start_subsubtest("rally status")
2927
self.click_three_in(target_system=target_system, target_component=target_component)
2928
mavproxy.send("rally status\n")
2929
mavproxy.expect("Have 3 of 3 rally items")
2930
mavproxy.send("rally clear\n")
2931
mavproxy.send("rally status\n")
2932
mavproxy.expect("Have 0 of 0 rally items")
2933
self.end_subsubtest("rally status")
2934
2935
self.start_subsubtest("rally undo")
2936
self.progress("Testing undo-remove")
2937
self.click_three_in(target_system=target_system, target_component=target_component)
2938
pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2939
self.progress("Removing first in list")
2940
mavproxy.send("rally remove 1\n")
2941
self.delay_sim_time(5)
2942
self.assert_mission_count_on_link(
2943
self.mav,
2944
2,
2945
target_system,
2946
target_component,
2947
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
2948
)
2949
mavproxy.send("rally undo\n")
2950
self.delay_sim_time(5)
2951
undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2952
self.check_rally_items_same(pure_items, undone_items)
2953
2954
self.progress("Testing undo-move")
2955
2956
pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2957
mavproxy.send("click 4.12345 4.987654\n")
2958
mavproxy.send("rally move 1\n")
2959
# move has already been tested, assume it works...
2960
self.delay_sim_time(5)
2961
mavproxy.send("rally undo\n")
2962
self.delay_sim_time(5)
2963
undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2964
self.check_rally_items_same(pure_items, undone_items)
2965
2966
self.end_subsubtest("rally undo")
2967
2968
self.start_subsubtest("rally update")
2969
self.click_three_in(target_system=target_system, target_component=target_component)
2970
pure_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2971
rally_update_tmpfilepath = self.buildlogs_path("rally-tmp-update.txt")
2972
mavproxy.send("rally save %s\n" % rally_update_tmpfilepath)
2973
self.delay_sim_time(5)
2974
self.progress("Moving waypoint")
2975
mavproxy.send("click 13.0 13.0\n")
2976
mavproxy.send("rally move 1\n")
2977
self.delay_sim_time(5)
2978
self.progress("Reverting to original")
2979
mavproxy.send("rally update %s\n" % rally_update_tmpfilepath)
2980
self.delay_sim_time(5)
2981
reverted_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2982
self.check_rally_items_same(pure_items, reverted_items)
2983
2984
self.progress("Making sure specifying a waypoint to be updated works")
2985
mavproxy.send("click 13.0 13.0\n")
2986
mavproxy.send("rally move 1\n")
2987
self.delay_sim_time(5)
2988
mavproxy.send("click 17.0 17.0\n")
2989
mavproxy.send("rally move 2\n")
2990
self.delay_sim_time(5)
2991
self.progress("Reverting to original item 2")
2992
mavproxy.send("rally update %s 2\n" % rally_update_tmpfilepath)
2993
self.delay_sim_time(5)
2994
reverted_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
2995
if reverted_items[0].x != 130000000:
2996
raise NotAchievedException("Expected item1 x to stay changed (got=%u want=%u)" % (reverted_items[0].x, 130000000))
2997
if reverted_items[1].x == 170000000:
2998
raise NotAchievedException("Expected item2 x to revert")
2999
3000
self.end_subsubtest("rally update")
3001
self.delay_sim_time(1)
3002
if self.get_parameter("RALLY_TOTAL") != 0:
3003
raise NotAchievedException("Failed to clear rally points")
3004
3005
self.stop_mavproxy(mavproxy)
3006
3007
# MANUAL> usage: rally <add|alt|changealt|clear|list|load|move|movemulti|param|remove|save|savecsv|savelocal|show|status|undo|update> # noqa
3008
3009
def RallyUploadDownload(self, target_system=1, target_component=1):
3010
'''Upload and download of rally'''
3011
old_srcSystem = self.mav.mav.srcSystem
3012
3013
self.drain_mav()
3014
try:
3015
item1_lat = int(2.0000 * 1e7)
3016
items = [
3017
self.mav.mav.mission_item_int_encode(
3018
target_system,
3019
target_component,
3020
0, # seq
3021
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3022
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3023
0, # current
3024
0, # autocontinue
3025
0, # p1
3026
0, # p2
3027
0, # p3
3028
0, # p4
3029
int(1.0000 * 1e7), # latitude
3030
int(1.0000 * 1e7), # longitude
3031
31.0000, # altitude
3032
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3033
self.mav.mav.mission_item_int_encode(
3034
target_system,
3035
target_component,
3036
1, # seq
3037
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3038
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3039
0, # current
3040
0, # autocontinue
3041
0, # p1
3042
0, # p2
3043
0, # p3
3044
0, # p4
3045
item1_lat, # latitude
3046
int(2.0000 * 1e7), # longitude
3047
32.0000, # altitude
3048
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3049
self.mav.mav.mission_item_int_encode(
3050
target_system,
3051
target_component,
3052
2, # seq
3053
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3054
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3055
0, # current
3056
0, # autocontinue
3057
0, # p1
3058
0, # p2
3059
0, # p3
3060
0, # p4
3061
int(3.0000 * 1e7), # latitude
3062
int(3.0000 * 1e7), # longitude
3063
33.0000, # altitude
3064
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3065
]
3066
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3067
items)
3068
downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3069
print("Got items (%s)" % str(items))
3070
if len(downloaded) != len(items):
3071
raise NotAchievedException(
3072
"Did not download correct number of items want=%u got=%u" %
3073
(len(downloaded), len(items)))
3074
3075
rally_total = self.get_parameter("RALLY_TOTAL")
3076
if rally_total != len(downloaded):
3077
raise NotAchievedException(
3078
"Unexpected rally point count: want=%u got=%u" %
3079
(len(items), rally_total))
3080
3081
self.progress("Pruning count by setting parameter (urgh)")
3082
self.set_parameter("RALLY_TOTAL", 2)
3083
downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3084
if len(downloaded) != 2:
3085
raise NotAchievedException(
3086
"Failed to prune rally points by setting parameter. want=%u got=%u" %
3087
(2, len(downloaded)))
3088
3089
self.progress("Uploading a third item using old protocol")
3090
new_item2_lat = int(6.0 * 1e7)
3091
self.set_parameter("RALLY_TOTAL", 3)
3092
self.mav.mav.rally_point_send(target_system,
3093
target_component,
3094
2, # sequence number
3095
3, # total count
3096
new_item2_lat,
3097
int(7.0 * 1e7),
3098
15,
3099
0, # "break" alt?!
3100
0, # "land dir"
3101
0) # flags
3102
downloaded = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3103
if len(downloaded) != 3:
3104
raise NotAchievedException(
3105
"resetting rally point count didn't change items returned")
3106
if downloaded[2].x != new_item2_lat:
3107
raise NotAchievedException(
3108
"Bad lattitude in downloaded item: want=%u got=%u" %
3109
(new_item2_lat, downloaded[2].x))
3110
3111
self.progress("Grabbing original item 1 using original protocol")
3112
self.mav.mav.rally_fetch_point_send(target_system,
3113
target_component,
3114
1)
3115
m = self.mav.recv_match(type="RALLY_POINT", blocking=True, timeout=1)
3116
if m.target_system != self.mav.source_system:
3117
raise NotAchievedException(
3118
"Bad target_system on received rally point (want=%u got=%u)" %
3119
(255, m.target_system))
3120
if m.target_component != self.mav.source_component: # autotest's component ID
3121
raise NotAchievedException("Bad target_component on received rally point")
3122
if m.lat != item1_lat:
3123
raise NotAchievedException("Bad latitude on received rally point")
3124
3125
self.start_subtest("Test upload lockout and timeout")
3126
self.progress("Starting upload from normal sysid")
3127
self.mav.mav.mission_count_send(target_system,
3128
target_component,
3129
len(items),
3130
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3131
self.drain_mav() # throw away requests for items
3132
self.mav.mav.srcSystem = 243
3133
3134
self.progress("Attempting upload from sysid=%u" %
3135
(self.mav.mav.srcSystem,))
3136
self.mav.mav.mission_count_send(target_system,
3137
target_component,
3138
len(items),
3139
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3140
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3141
want_type=mavutil.mavlink.MAV_MISSION_DENIED)
3142
3143
self.progress("Attempting download from sysid=%u" %
3144
(self.mav.mav.srcSystem,))
3145
self.mav.mav.mission_request_list_send(target_system,
3146
target_component,
3147
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3148
3149
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3150
want_type=mavutil.mavlink.MAV_MISSION_DENIED)
3151
3152
# wait for the upload from sysid=1 to time out:
3153
tstart = self.get_sim_time()
3154
got_statustext = False
3155
got_ack = False
3156
while True:
3157
if got_statustext and got_ack:
3158
self.progress("Got both ack and statustext")
3159
break
3160
if self.get_sim_time_cached() - tstart > 100:
3161
raise NotAchievedException("Did not get both ack and statustext")
3162
m = self.mav.recv_match(type=['STATUSTEXT', 'MISSION_ACK'],
3163
blocking=True,
3164
timeout=1)
3165
if m is None:
3166
continue
3167
self.progress("Got (%s)" % str(m))
3168
if m.get_type() == 'STATUSTEXT':
3169
if "upload timeout" in m.text:
3170
got_statustext = True
3171
self.progress("Received desired statustext")
3172
continue
3173
if m.get_type() == 'MISSION_ACK':
3174
if m.target_system != old_srcSystem:
3175
raise NotAchievedException("Incorrect sourcesystem")
3176
if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:
3177
raise NotAchievedException("Incorrect result")
3178
if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_RALLY:
3179
raise NotAchievedException("Incorrect mission_type")
3180
got_ack = True
3181
self.progress("Received desired ACK")
3182
continue
3183
raise NotAchievedException("Huh?")
3184
3185
self.progress("Now trying to upload empty mission after timeout")
3186
self.mav.mav.mission_count_send(target_system,
3187
target_component,
3188
0,
3189
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3190
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3191
3192
self.drain_mav()
3193
self.start_subtest("Check rally upload/download across separate links")
3194
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3195
items)
3196
self.progress("ensure a mavlink1 connection can't do anything useful with new item types")
3197
self.set_parameter("SERIAL2_PROTOCOL", 1)
3198
self.reboot_sitl()
3199
mav2 = mavutil.mavlink_connection("tcp:localhost:5763",
3200
robust_parsing=True,
3201
source_system=7,
3202
source_component=7)
3203
mav2.mav.mission_request_list_send(target_system,
3204
target_component,
3205
mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3206
# so this looks a bit odd; the other end isn't sending
3207
# mavlink2 so can't fill in the extension here.
3208
self.assert_receive_mission_ack(
3209
mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
3210
want_type=mavutil.mavlink.MAV_MISSION_UNSUPPORTED,
3211
mav=mav2,
3212
)
3213
# this relies on magic upgrade to serial2:
3214
self.set_parameter("SERIAL2_PROTOCOL", 2)
3215
expected_count = 3
3216
self.progress("Assert mission count on new link")
3217
self.assert_mission_count_on_link(
3218
mav2,
3219
expected_count,
3220
target_system,
3221
target_component,
3222
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3223
self.progress("Assert mission count on original link")
3224
self.assert_mission_count_on_link(
3225
self.mav,
3226
expected_count,
3227
target_system,
3228
target_component,
3229
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3230
self.progress("Get first item on new link")
3231
3232
def drain_self_mav_fn():
3233
self.drain_mav(self.mav)
3234
m2 = self.get_mission_item_int_on_link(
3235
2,
3236
mav2,
3237
target_system,
3238
target_component,
3239
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3240
delay_fn=drain_self_mav_fn)
3241
self.progress("Get first item on original link")
3242
m = self.get_mission_item_int_on_link(
3243
2,
3244
self.mav,
3245
target_system,
3246
target_component,
3247
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3248
if m2.x != m.x:
3249
raise NotAchievedException("mission items do not match (%d vs %d)" % (m2.x, m.x))
3250
self.get_mission_item_on_link(2, self.mav, target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3251
# ensure we get nacks for bad mission item requests:
3252
self.mav.mav.mission_request_send(target_system,
3253
target_component,
3254
65,
3255
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3256
self.assert_receive_mission_ack(
3257
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3258
want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE,
3259
)
3260
self.mav.mav.mission_request_int_send(target_system,
3261
target_component,
3262
65,
3263
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3264
self.assert_receive_mission_ack(
3265
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3266
want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE,
3267
)
3268
3269
self.start_subtest("Should enforce items come from correct GCS")
3270
self.drain_mav(unparsed=True)
3271
self.mav.mav.mission_count_send(target_system,
3272
target_component,
3273
1,
3274
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3275
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)
3276
self.progress("Attempting to upload from bad sysid")
3277
old_sysid = self.mav.mav.srcSystem
3278
self.mav.mav.srcSystem = 17
3279
items[0].pack(self.mav.mav)
3280
self.drain_mav(unparsed=True)
3281
self.mav.mav.send(items[0])
3282
self.mav.mav.srcSystem = old_sysid
3283
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3284
want_type=mavutil.mavlink.MAV_MISSION_DENIED,
3285
target_system=17)
3286
self.progress("Sending from correct sysid")
3287
items[0].pack(self.mav.mav)
3288
self.drain_mav(unparsed=True)
3289
self.mav.mav.send(items[0])
3290
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3291
3292
self.drain_mav()
3293
self.drain_all_pexpects()
3294
3295
self.start_subtest("Attempt to send item on different link to that which we are sending requests on")
3296
self.progress("Sending count")
3297
self.drain_mav(unparsed=True)
3298
self.mav.mav.mission_count_send(target_system,
3299
target_component,
3300
2,
3301
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3302
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)
3303
old_mav2_system = mav2.mav.srcSystem
3304
old_mav2_component = mav2.mav.srcComponent
3305
mav2.mav.srcSystem = self.mav.mav.srcSystem
3306
mav2.mav.srcComponent = self.mav.mav.srcComponent
3307
self.progress("Sending item on second link")
3308
# note that the routing table in ArduPilot now will say
3309
# this sysid/compid is on both links which may cause
3310
# weirdness...
3311
items[0].pack(mav2.mav)
3312
self.drain_mav(mav=self.mav, unparsed=True)
3313
mav2.mav.send(items[0])
3314
mav2.mav.srcSystem = old_mav2_system
3315
mav2.mav.srcComponent = old_mav2_component
3316
# we continue to receive requests on the original link:
3317
m = self.assert_receive_message('MISSION_REQUEST', timeout=1)
3318
if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_RALLY:
3319
raise NotAchievedException("Mission request of incorrect type")
3320
if m.seq != 1:
3321
raise NotAchievedException("Unexpected sequence number (expected=%u got=%u)" % (1, m.seq))
3322
items[1].pack(self.mav.mav)
3323
self.drain_mav(unparsed=True)
3324
self.mav.mav.send(items[1])
3325
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3326
3327
self.drain_mav()
3328
self.drain_all_pexpects()
3329
3330
self.start_subtest("Upload mission and rally points at same time")
3331
self.progress("Sending rally count")
3332
self.drain_mav(unparsed=True)
3333
self.mav.mav.mission_count_send(target_system,
3334
target_component,
3335
3,
3336
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3337
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 0)
3338
3339
self.progress("Sending wp count")
3340
self.mav.mav.mission_count_send(target_system,
3341
target_component,
3342
3,
3343
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3344
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 0)
3345
3346
self.progress("Answering request for mission item 0")
3347
self.drain_mav(mav=self.mav, unparsed=True)
3348
self.mav.mav.mission_item_int_send(
3349
target_system,
3350
target_component,
3351
0, # seq
3352
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3353
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3354
0, # current
3355
0, # autocontinue
3356
0, # p1
3357
0, # p2
3358
0, # p3
3359
0, # p4
3360
int(1.1000 * 1e7), # latitude
3361
int(1.2000 * 1e7), # longitude
3362
321.0000, # altitude
3363
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3364
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 1)
3365
3366
self.progress("Answering request for rally point 0")
3367
items[0].pack(self.mav.mav)
3368
self.drain_mav(unparsed=True)
3369
self.mav.mav.send(items[0])
3370
self.progress("Expecting request for rally item 1")
3371
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 1)
3372
self.progress("Answering request for rally point 1")
3373
items[1].pack(self.mav.mav)
3374
self.drain_mav(unparsed=True)
3375
self.mav.mav.send(items[1])
3376
self.progress("Expecting request for rally item 2")
3377
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 2)
3378
3379
self.progress("Answering request for rally point 2")
3380
items[2].pack(self.mav.mav)
3381
self.drain_mav(unparsed=True)
3382
self.mav.mav.send(items[2])
3383
self.progress("Expecting mission ack for rally")
3384
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3385
3386
self.progress("Answering request for waypoints item 1")
3387
self.drain_mav(unparsed=True)
3388
self.mav.mav.mission_item_int_send(
3389
target_system,
3390
target_component,
3391
1, # seq
3392
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3393
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3394
0, # current
3395
0, # autocontinue
3396
0, # p1
3397
0, # p2
3398
0, # p3
3399
0, # p4
3400
int(1.1000 * 1e7), # latitude
3401
int(1.2000 * 1e7), # longitude
3402
321.0000, # altitude
3403
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3404
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, 2)
3405
3406
self.progress("Answering request for waypoints item 2")
3407
self.drain_mav(unparsed=True)
3408
self.mav.mav.mission_item_int_send(
3409
target_system,
3410
target_component,
3411
2, # seq
3412
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3413
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3414
0, # current
3415
0, # autocontinue
3416
0, # p1
3417
0, # p2
3418
0, # p3
3419
0, # p4
3420
int(1.1000 * 1e7), # latitude
3421
int(1.2000 * 1e7), # longitude
3422
321.0000, # altitude
3423
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3424
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3425
3426
self.start_subtest("Test write-partial-list")
3427
self.progress("Clearing rally points using count-send")
3428
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3429
target_system=target_system,
3430
target_component=target_component)
3431
self.progress("Should not be able to set items completely past the waypoint count")
3432
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3433
items)
3434
self.drain_mav(unparsed=True)
3435
self.mav.mav.mission_write_partial_list_send(
3436
target_system,
3437
target_component,
3438
17,
3439
20,
3440
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3441
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3442
want_type=mavutil.mavlink.MAV_MISSION_ERROR)
3443
3444
self.progress("Should not be able to set items overlapping the waypoint count")
3445
self.drain_mav(unparsed=True)
3446
self.mav.mav.mission_write_partial_list_send(
3447
target_system,
3448
target_component,
3449
0,
3450
20,
3451
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3452
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3453
want_type=mavutil.mavlink.MAV_MISSION_ERROR)
3454
3455
self.progress("try to overwrite items 1 and 2")
3456
self.drain_mav(unparsed=True)
3457
self.mav.mav.mission_write_partial_list_send(
3458
target_system,
3459
target_component,
3460
1,
3461
2,
3462
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3463
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 1)
3464
self.progress("Try shoving up an incorrectly sequenced item")
3465
self.drain_mav(unparsed=True)
3466
self.mav.mav.mission_item_int_send(
3467
target_system,
3468
target_component,
3469
0, # seq
3470
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3471
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3472
0, # current
3473
0, # autocontinue
3474
0, # p1
3475
0, # p2
3476
0, # p3
3477
0, # p4
3478
int(1.1000 * 1e7), # latitude
3479
int(1.2000 * 1e7), # longitude
3480
321.0000, # altitude
3481
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3482
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3483
want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE)
3484
3485
self.progress("Try shoving up an incorrectly sequenced item (but within band)")
3486
self.drain_mav(unparsed=True)
3487
self.mav.mav.mission_item_int_send(
3488
target_system,
3489
target_component,
3490
2, # seq
3491
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3492
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3493
0, # current
3494
0, # autocontinue
3495
0, # p1
3496
0, # p2
3497
0, # p3
3498
0, # p4
3499
int(1.1000 * 1e7), # latitude
3500
int(1.2000 * 1e7), # longitude
3501
321.0000, # altitude
3502
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3503
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3504
want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE)
3505
3506
self.progress("Now provide correct item")
3507
item1_latitude = int(1.2345 * 1e7)
3508
self.drain_mav(unparsed=True)
3509
self.mav.mav.mission_item_int_send(
3510
target_system,
3511
target_component,
3512
1, # seq
3513
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
3514
mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT,
3515
0, # current
3516
0, # autocontinue
3517
0, # p1
3518
0, # p2
3519
0, # p3
3520
0, # p4
3521
item1_latitude, # latitude
3522
int(1.2000 * 1e7), # longitude
3523
321.0000, # altitude
3524
mavutil.mavlink.MAV_MISSION_TYPE_RALLY),
3525
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, 2)
3526
self.progress("Answering request for rally point 2")
3527
items[2].pack(self.mav.mav)
3528
self.drain_mav(unparsed=True)
3529
self.mav.mav.send(items[2])
3530
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3531
self.progress("TODO: ensure partial mission write was good")
3532
3533
self.start_subtest("clear mission types")
3534
self.assert_mission_count_on_link(
3535
self.mav,
3536
3,
3537
target_system,
3538
target_component,
3539
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3540
self.assert_mission_count_on_link(
3541
self.mav,
3542
3,
3543
target_system,
3544
target_component,
3545
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3546
self.drain_mav(unparsed=True)
3547
self.mav.mav.mission_clear_all_send(target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3548
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3549
self.assert_mission_count_on_link(
3550
self.mav,
3551
0,
3552
target_system,
3553
target_component,
3554
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3555
self.assert_mission_count_on_link(
3556
self.mav,
3557
3,
3558
target_system,
3559
target_component,
3560
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3561
self.drain_mav(unparsed=True)
3562
self.mav.mav.mission_clear_all_send(target_system, target_component, mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3563
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3564
self.assert_mission_count_on_link(
3565
self.mav,
3566
0,
3567
target_system,
3568
target_component,
3569
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3570
self.assert_mission_count_on_link(
3571
self.mav,
3572
0,
3573
target_system,
3574
target_component,
3575
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3576
3577
self.start_subtest("try sending out-of-range counts")
3578
self.drain_mav(unparsed=True)
3579
self.mav.mav.mission_count_send(target_system,
3580
target_component,
3581
1,
3582
230)
3583
self.assert_receive_mission_ack(230,
3584
want_type=mavutil.mavlink.MAV_MISSION_UNSUPPORTED)
3585
self.drain_mav(unparsed=True)
3586
self.mav.mav.mission_count_send(target_system,
3587
target_component,
3588
16000,
3589
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
3590
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
3591
want_type=mavutil.mavlink.MAV_MISSION_NO_SPACE)
3592
3593
except Exception as e:
3594
self.progress("Received exception (%s)" % self.get_exception_stacktrace(e))
3595
self.mav.mav.srcSystem = old_srcSystem
3596
raise e
3597
self.reboot_sitl()
3598
3599
def ClearMission(self, target_system=1, target_component=1):
3600
'''check mission clearing'''
3601
3602
self.start_subtest("Clear via mission_clear_all message")
3603
self.upload_simple_relhome_mission([
3604
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
3605
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
3606
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
3607
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
3608
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
3609
])
3610
self.set_current_waypoint(3)
3611
3612
self.mav.mav.mission_clear_all_send(
3613
target_system,
3614
target_component,
3615
mavutil.mavlink.MAV_MISSION_TYPE_MISSION
3616
)
3617
3618
self.assert_current_waypoint(0)
3619
3620
self.drain_mav()
3621
3622
self.start_subtest("No clear mission while it is being uploaded by a different node")
3623
mav2 = mavutil.mavlink_connection("tcp:localhost:5763",
3624
robust_parsing=True,
3625
source_system=7,
3626
source_component=7)
3627
self.context_push()
3628
self.context_collect("MISSION_REQUEST")
3629
mav2.mav.mission_count_send(target_system,
3630
target_component,
3631
17,
3632
mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3633
ack = self.assert_receive_message('MISSION_REQUEST', check_context=True, mav=mav2)
3634
self.context_pop()
3635
3636
self.context_push()
3637
self.context_collect("MISSION_ACK")
3638
self.mav.mav.mission_clear_all_send(
3639
target_system,
3640
target_component,
3641
mavutil.mavlink.MAV_MISSION_TYPE_MISSION
3642
)
3643
ack = self.assert_receive_message('MISSION_ACK', check_context=True)
3644
self.assert_message_field_values(ack, {
3645
"type": mavutil.mavlink.MAV_MISSION_DENIED,
3646
})
3647
self.context_pop()
3648
3649
self.progress("Test cancel upload from second connection")
3650
self.context_push()
3651
self.context_collect("MISSION_ACK")
3652
mav2.mav.mission_clear_all_send(
3653
target_system,
3654
target_component,
3655
mavutil.mavlink.MAV_MISSION_TYPE_MISSION
3656
)
3657
ack = self.assert_receive_message('MISSION_ACK', mav=mav2, check_context=True)
3658
self.assert_message_field_values(ack, {
3659
"type": mavutil.mavlink.MAV_MISSION_ACCEPTED,
3660
})
3661
self.context_pop()
3662
mav2.close()
3663
del mav2
3664
3665
def GCSMission(self):
3666
'''check MAVProxy's waypoint handling of missions'''
3667
3668
target_system = 1
3669
target_component = 1
3670
mavproxy = self.start_mavproxy()
3671
mavproxy.send('wp clear\n')
3672
self.delay_sim_time(1)
3673
if self.get_parameter("MIS_TOTAL") != 0:
3674
raise NotAchievedException("Failed to clear mission")
3675
m = self.assert_receive_message('MISSION_CURRENT', timeout=5, verbose=True)
3676
if m.seq != 0:
3677
raise NotAchievedException("Bad mission current")
3678
self.load_mission_using_mavproxy(mavproxy, "rover-gripper-mission.txt")
3679
set_wp = 1
3680
mavproxy.send('wp set %u\n' % set_wp)
3681
self.wait_current_waypoint(set_wp)
3682
3683
self.start_subsubtest("wp changealt")
3684
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3685
changealt_item = 1
3686
# oldalt = downloaded_items[changealt_item].z
3687
want_newalt = 37.2
3688
mavproxy.send('wp changealt %u %f\n' % (changealt_item, want_newalt))
3689
self.delay_sim_time(15)
3690
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3691
if abs(downloaded_items[changealt_item].z - want_newalt) > 0.0001:
3692
raise NotAchievedException(
3693
"changealt didn't (want=%f got=%f)" %
3694
(want_newalt, downloaded_items[changealt_item].z))
3695
self.end_subsubtest("wp changealt")
3696
3697
self.start_subsubtest("wp sethome")
3698
new_home_lat = 3.14159
3699
new_home_lng = 2.71828
3700
mavproxy.send('click %f %f\n' % (new_home_lat, new_home_lng))
3701
mavproxy.send('wp sethome\n')
3702
self.delay_sim_time(5)
3703
# any way to close the loop on this one?
3704
# downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3705
# if abs(downloaded_items[0].x - new_home_lat) > 0.0001:
3706
# raise NotAchievedException("wp sethome didn't work")
3707
# if abs(downloaded_items[0].y - new_home_lng) > 0.0001:
3708
# raise NotAchievedException("wp sethome didn't work")
3709
self.end_subsubtest("wp sethome")
3710
3711
self.start_subsubtest("wp slope")
3712
mavproxy.send('wp slope\n')
3713
mavproxy.expect("WP3: slope 0.1")
3714
self.delay_sim_time(5)
3715
self.end_subsubtest("wp slope")
3716
3717
if not self.mavproxy_can_do_mision_item_protocols():
3718
# adding based on click location yet to be merged into MAVProxy
3719
return
3720
3721
self.start_subsubtest("wp split")
3722
mavproxy.send("wp clear\n")
3723
self.delay_sim_time(5)
3724
mavproxy.send("wp list\n")
3725
self.delay_sim_time(5)
3726
items = [
3727
None,
3728
self.mav.mav.mission_item_int_encode(
3729
target_system,
3730
target_component,
3731
1, # seq
3732
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3733
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3734
0, # current
3735
0, # autocontinue
3736
0, # p1
3737
0, # p2
3738
0, # p3
3739
0, # p4
3740
int(1.0 * 1e7), # latitude
3741
int(1.0 * 1e7), # longitude
3742
33.0000, # altitude
3743
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3744
self.mav.mav.mission_item_int_encode(
3745
target_system,
3746
target_component,
3747
2, # seq
3748
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3749
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3750
0, # current
3751
0, # autocontinue
3752
0, # p1
3753
0, # p2
3754
0, # p3
3755
0, # p4
3756
int(2.0 * 1e7), # latitude
3757
int(2.0 * 1e7), # longitude
3758
33.0000, # altitude
3759
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3760
]
3761
mavproxy.send("click 5 5\n") # space for home position
3762
mavproxy.send("wp add\n")
3763
self.delay_sim_time(5)
3764
self.click_location_from_item(mavproxy, items[1])
3765
mavproxy.send("wp add\n")
3766
self.delay_sim_time(5)
3767
self.click_location_from_item(mavproxy, items[2])
3768
mavproxy.send("wp add\n")
3769
self.delay_sim_time(5)
3770
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3771
self.check_mission_waypoint_items_same(items, downloaded_items)
3772
mavproxy.send("wp split 2\n")
3773
self.delay_sim_time(5)
3774
items_with_split_in = [
3775
items[0],
3776
items[1],
3777
self.mav.mav.mission_item_int_encode(
3778
target_system,
3779
target_component,
3780
2, # seq
3781
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3782
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
3783
0, # current
3784
0, # autocontinue
3785
0, # p1
3786
0, # p2
3787
0, # p3
3788
0, # p4
3789
int(1.5 * 1e7), # latitude
3790
int(1.5 * 1e7), # longitude
3791
33.0000, # altitude
3792
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
3793
items[2],
3794
]
3795
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION)
3796
self.check_mission_waypoint_items_same(items_with_split_in,
3797
downloaded_items)
3798
3799
self.stop_mavproxy(mavproxy)
3800
3801
# MANUAL> usage: wp <changealt|clear|draw|editor|list|load|loop|move|movemulti|noflyadd|param|remove|save|savecsv|savelocal|set|sethome|show|slope|split|status|undo|update> # noqa
3802
3803
def wait_location_sending_target(self, loc, target_system=1, target_component=1, timeout=60, max_delta=2):
3804
tstart = self.get_sim_time()
3805
last_sent = 0
3806
3807
type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +
3808
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +
3809
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +
3810
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +
3811
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +
3812
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +
3813
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +
3814
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)
3815
3816
self.change_mode('GUIDED')
3817
tstart = self.get_sim_time()
3818
while True:
3819
now = self.get_sim_time_cached()
3820
if now - tstart > timeout:
3821
raise AutoTestTimeoutException("Did not get to location")
3822
if now - last_sent > 10:
3823
last_sent = now
3824
self.mav.mav.set_position_target_global_int_send(
3825
0,
3826
target_system,
3827
target_component,
3828
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3829
type_mask,
3830
int(loc.lat * 1.0e7),
3831
int(loc.lng * 1.0e7),
3832
0, # alt
3833
0, # x-ve
3834
0, # y-vel
3835
0, # z-vel
3836
0, # afx
3837
0, # afy
3838
0, # afz
3839
0, # yaw,
3840
0, # yaw-rate
3841
)
3842
m = self.mav.recv_match(blocking=True,
3843
timeout=1)
3844
if m is None:
3845
continue
3846
t = m.get_type()
3847
if t == "POSITION_TARGET_GLOBAL_INT":
3848
self.progress("Target: (%s)" % str(m), send_statustext=False)
3849
elif t == "GLOBAL_POSITION_INT":
3850
self.progress("Position: (%s)" % str(m), send_statustext=False)
3851
delta = self.get_distance(
3852
mavutil.location(m.lat * 1e-7, m.lon * 1e-7, 0, 0),
3853
loc)
3854
self.progress("delta: %s" % str(delta), send_statustext=False)
3855
if delta < max_delta:
3856
self.progress("Reached destination")
3857
3858
def drive_to_location(self, loc, tolerance=1, timeout=30, target_system=1, target_component=1):
3859
self.assert_mode('GUIDED')
3860
3861
type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +
3862
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +
3863
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +
3864
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +
3865
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +
3866
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +
3867
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +
3868
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)
3869
3870
last_sent = 0
3871
tstart = self.get_sim_time()
3872
while True:
3873
now = self.get_sim_time_cached()
3874
if now - tstart > timeout:
3875
raise NotAchievedException("Did not get to location")
3876
if now - last_sent > 10:
3877
last_sent = now
3878
self.mav.mav.set_position_target_global_int_send(
3879
0,
3880
target_system,
3881
target_component,
3882
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3883
type_mask,
3884
int(loc.lat * 1.0e7),
3885
int(loc.lng * 1.0e7),
3886
0, # alt
3887
0, # x-ve
3888
0, # y-vel
3889
0, # z-vel
3890
0, # afx
3891
0, # afy
3892
0, # afz
3893
0, # yaw,
3894
0, # yaw-rate
3895
)
3896
if self.get_distance(self.mav.location(), loc) > tolerance:
3897
continue
3898
return
3899
3900
def drive_somewhere_breach_boundary_and_rtl(self, loc, target_system=1, target_component=1, timeout=60):
3901
tstart = self.get_sim_time()
3902
last_sent = 0
3903
seen_fence_breach = False
3904
3905
type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +
3906
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +
3907
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +
3908
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +
3909
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +
3910
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +
3911
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +
3912
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)
3913
3914
self.change_mode('GUIDED')
3915
while True:
3916
now = self.get_sim_time_cached()
3917
if now - tstart > timeout:
3918
raise NotAchievedException("Did not breach boundary + RTL")
3919
if now - last_sent > 10:
3920
last_sent = now
3921
self.mav.mav.set_position_target_global_int_send(
3922
0,
3923
target_system,
3924
target_component,
3925
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3926
type_mask,
3927
int(loc.lat * 1.0e7),
3928
int(loc.lng * 1.0e7),
3929
0, # alt
3930
0, # x-ve
3931
0, # y-vel
3932
0, # z-vel
3933
0, # afx
3934
0, # afy
3935
0, # afz
3936
0, # yaw,
3937
0, # yaw-rate
3938
)
3939
m = self.mav.recv_match(blocking=True,
3940
timeout=1)
3941
if m is None:
3942
continue
3943
t = m.get_type()
3944
if t == "POSITION_TARGET_GLOBAL_INT":
3945
self.progress("Target: (%s)" % str(m))
3946
elif t == "GLOBAL_POSITION_INT":
3947
self.progress("Position: (%s)" % str(m))
3948
elif t == "FENCE_STATUS":
3949
self.progress("Fence: %s" % str(m))
3950
if m.breach_status != 0:
3951
seen_fence_breach = True
3952
self.progress("Fence breach detected!")
3953
if m.breach_type != mavutil.mavlink.FENCE_BREACH_BOUNDARY:
3954
raise NotAchievedException("Breach of unexpected type")
3955
if self.mode_is("RTL", cached=True) and seen_fence_breach:
3956
break
3957
self.wait_distance_to_home(3, 7, timeout=30)
3958
3959
def drive_somewhere_stop_at_boundary(self,
3960
loc,
3961
expected_stopping_point,
3962
expected_distance_epsilon=1.0,
3963
target_system=1,
3964
target_component=1,
3965
timeout=120):
3966
tstart = self.get_sim_time()
3967
last_sent = 0
3968
3969
type_mask = (mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE +
3970
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE +
3971
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE +
3972
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE +
3973
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE +
3974
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE +
3975
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE +
3976
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE)
3977
3978
self.change_mode('GUIDED')
3979
at_stopping_point = False
3980
while True:
3981
now = self.get_sim_time_cached()
3982
if now - tstart > timeout:
3983
raise NotAchievedException("Did not arrive and stop at boundary")
3984
if now - last_sent > 10:
3985
last_sent = now
3986
self.mav.mav.set_position_target_global_int_send(
3987
0,
3988
target_system,
3989
target_component,
3990
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
3991
type_mask,
3992
int(loc.lat * 1.0e7),
3993
int(loc.lng * 1.0e7),
3994
0, # alt
3995
0, # x-ve
3996
0, # y-vel
3997
0, # z-vel
3998
0, # afx
3999
0, # afy
4000
0, # afz
4001
0, # yaw,
4002
0, # yaw-rate
4003
)
4004
m = self.mav.recv_match(blocking=True,
4005
timeout=1)
4006
if m is None:
4007
continue
4008
t = m.get_type()
4009
if t == "POSITION_TARGET_GLOBAL_INT":
4010
print("Target: (%s)" % str(m))
4011
elif t == "GLOBAL_POSITION_INT":
4012
print("Position: (%s)" % str(m))
4013
delta = self.get_distance(
4014
mavutil.location(m.lat * 1e-7, m.lon * 1e-7, 0, 0),
4015
mavutil.location(expected_stopping_point.lat,
4016
expected_stopping_point.lng,
4017
0,
4018
0))
4019
print("delta: %s want_delta<%f" % (str(delta), expected_distance_epsilon))
4020
at_stopping_point = delta < expected_distance_epsilon
4021
elif t == "VFR_HUD":
4022
print("groundspeed: %f" % m.groundspeed)
4023
if at_stopping_point:
4024
if m.groundspeed < 1:
4025
self.progress("Seemed to have stopped at stopping point")
4026
return
4027
4028
def assert_fence_breached(self):
4029
m = self.assert_receive_message('FENCE_STATUS', timeout=10)
4030
if m.breach_status != 1:
4031
raise NotAchievedException("Expected to be breached")
4032
4033
def wait_fence_not_breached(self, timeout=5):
4034
tstart = self.get_sim_time()
4035
while True:
4036
if self.get_sim_time_cached() - tstart > timeout:
4037
raise AutoTestTimeoutException("Fence remains breached")
4038
m = self.mav.recv_match(type='FENCE_STATUS',
4039
blocking=True,
4040
timeout=1)
4041
if m is None:
4042
self.progress("No FENCE_STATUS received")
4043
continue
4044
self.progress("STATUS: %s" % str(m))
4045
if m.breach_status == 0:
4046
break
4047
4048
def test_poly_fence_noarms(self, target_system=1, target_component=1):
4049
'''various tests to ensure we can't arm when in breach of a polyfence'''
4050
self.start_subtest("Ensure PolyFence arming checks work")
4051
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4052
target_system=target_system,
4053
target_component=target_component)
4054
self.set_parameters({
4055
"FENCE_TYPE": 2, # circle only
4056
})
4057
self.delay_sim_time(5) # let breaches clear
4058
# FIXME: should we allow this?
4059
self.progress("Ensure we can arm with no poly in place")
4060
self.change_mode("GUIDED")
4061
self.wait_ready_to_arm()
4062
self.arm_vehicle()
4063
self.disarm_vehicle()
4064
self.set_parameters({
4065
"FENCE_TYPE": 6, # polyfence + circle
4066
})
4067
4068
self.test_poly_fence_noarms_exclusion_circle(target_system=target_system,
4069
target_component=target_component)
4070
self.test_poly_fence_noarms_inclusion_circle(target_system=target_system,
4071
target_component=target_component)
4072
self.test_poly_fence_noarms_exclusion_polyfence(target_system=target_system,
4073
target_component=target_component)
4074
self.test_poly_fence_noarms_inclusion_polyfence(target_system=target_system,
4075
target_component=target_component)
4076
4077
def test_poly_fence_noarms_exclusion_circle(self, target_system=1, target_component=1):
4078
self.start_subtest("Ensure not armable when within an exclusion circle")
4079
4080
here = self.mav.location()
4081
4082
items = [
4083
self.mav.mav.mission_item_int_encode(
4084
target_system,
4085
target_component,
4086
0, # seq
4087
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4088
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
4089
0, # current
4090
0, # autocontinue
4091
5, # p1 - radius
4092
0, # p2
4093
0, # p3
4094
0, # p4
4095
int(here.lat * 1e7), # latitude
4096
int(here.lng * 1e7), # longitude
4097
33.0000, # altitude
4098
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
4099
self.mav.mav.mission_item_int_encode(
4100
target_system,
4101
target_component,
4102
1, # seq
4103
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4104
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
4105
0, # current
4106
0, # autocontinue
4107
5, # p1 - radius
4108
0, # p2
4109
0, # p3
4110
0, # p4
4111
int(self.offset_location_ne(here, 100, 100).lat * 1e7), # latitude
4112
int(here.lng * 1e7), # longitude
4113
33.0000, # altitude
4114
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
4115
]
4116
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4117
items)
4118
self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz
4119
self.drain_mav()
4120
self.assert_fence_breached()
4121
try:
4122
self.arm_motors_with_rc_input()
4123
except NotAchievedException:
4124
pass
4125
if self.armed():
4126
raise NotAchievedException(
4127
"Armed when within exclusion zone")
4128
4129
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4130
[])
4131
self.wait_fence_not_breached()
4132
4133
def test_poly_fence_noarms_inclusion_circle(self, target_system=1, target_component=1):
4134
self.start_subtest("Ensure not armable when outside an inclusion circle (but within another")
4135
4136
here = self.mav.location()
4137
4138
items = [
4139
self.mav.mav.mission_item_int_encode(
4140
target_system,
4141
target_component,
4142
0, # seq
4143
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4144
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
4145
0, # current
4146
0, # autocontinue
4147
5, # p1 - radius
4148
0, # p2
4149
0, # p3
4150
0, # p4
4151
int(here.lat * 1e7), # latitude
4152
int(here.lng * 1e7), # longitude
4153
33.0000, # altitude
4154
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
4155
self.mav.mav.mission_item_int_encode(
4156
target_system,
4157
target_component,
4158
1, # seq
4159
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4160
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION,
4161
0, # current
4162
0, # autocontinue
4163
5, # p1 - radius
4164
0, # p2
4165
0, # p3
4166
0, # p4
4167
int(self.offset_location_ne(here, 100, 100).lat * 1e7), # latitude
4168
int(here.lng * 1e7), # longitude
4169
33.0000, # altitude
4170
mavutil.mavlink.MAV_MISSION_TYPE_FENCE),
4171
]
4172
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4173
items)
4174
self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz
4175
self.drain_mav()
4176
self.assert_fence_breached()
4177
try:
4178
self.arm_motors_with_rc_input()
4179
except NotAchievedException:
4180
pass
4181
if self.armed():
4182
raise NotAchievedException(
4183
"Armed when outside an inclusion zone")
4184
4185
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4186
[])
4187
self.wait_fence_not_breached()
4188
4189
def test_poly_fence_noarms_exclusion_polyfence(self, target_system=1, target_component=1):
4190
self.start_subtest("Ensure not armable when inside an exclusion polyfence (but outside another")
4191
4192
here = self.mav.location()
4193
4194
self.upload_fences_from_locations([
4195
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4196
# east
4197
self.offset_location_ne(here, -50, 20), # bl
4198
self.offset_location_ne(here, 50, 20), # br
4199
self.offset_location_ne(here, 50, 40), # tr
4200
self.offset_location_ne(here, -50, 40), # tl,
4201
]),
4202
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4203
# over the top of the vehicle
4204
self.offset_location_ne(here, -50, -50), # bl
4205
self.offset_location_ne(here, -50, 50), # br
4206
self.offset_location_ne(here, 50, 50), # tr
4207
self.offset_location_ne(here, 50, -50), # tl,
4208
]),
4209
])
4210
self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz
4211
self.drain_mav()
4212
self.assert_fence_breached()
4213
try:
4214
self.arm_motors_with_rc_input()
4215
except NotAchievedException:
4216
pass
4217
if self.armed():
4218
raise NotAchievedException(
4219
"Armed when within polygon exclusion zone")
4220
4221
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4222
[])
4223
self.wait_fence_not_breached()
4224
4225
def test_poly_fence_noarms_inclusion_polyfence(self, target_system=1, target_component=1):
4226
self.start_subtest("Ensure not armable when outside an inclusion polyfence (but within another")
4227
4228
here = self.mav.location()
4229
4230
self.upload_fences_from_locations([
4231
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
4232
# east
4233
self.offset_location_ne(here, -50, 20), # bl
4234
self.offset_location_ne(here, 50, 20), # br
4235
self.offset_location_ne(here, 50, 40), # tr
4236
self.offset_location_ne(here, -50, 40), # tl,
4237
]),
4238
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
4239
# over the top of the vehicle
4240
self.offset_location_ne(here, -50, -50), # bl
4241
self.offset_location_ne(here, -50, 50), # br
4242
self.offset_location_ne(here, 50, 50), # tr
4243
self.offset_location_ne(here, 50, -50), # tl,
4244
]),
4245
])
4246
self.delay_sim_time(5) # ArduPilot only checks for breaches @1Hz
4247
self.drain_mav()
4248
self.assert_fence_breached()
4249
try:
4250
self.arm_motors_with_rc_input()
4251
except NotAchievedException:
4252
pass
4253
if self.armed():
4254
raise NotAchievedException(
4255
"Armed when outside polygon inclusion zone")
4256
4257
self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4258
[])
4259
self.wait_fence_not_breached()
4260
4261
def test_fence_upload_timeouts_1(self, target_system=1, target_component=1):
4262
self.start_subtest("fence_upload timeouts 1")
4263
self.progress("Telling victim there will be one item coming")
4264
self.mav.mav.mission_count_send(target_system,
4265
target_component,
4266
1,
4267
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4268
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],
4269
blocking=True,
4270
timeout=1)
4271
self.progress("Got (%s)" % str(m))
4272
if m is None:
4273
raise NotAchievedException("Did not get ACK or mission request")
4274
4275
if m.get_type() == "MISSION_ACK":
4276
raise NotAchievedException("Expected MISSION_REQUEST")
4277
4278
if m.seq != 0:
4279
raise NotAchievedException("Expected request for seq=0")
4280
4281
if m.target_system != self.mav.mav.srcSystem:
4282
raise NotAchievedException("Incorrect target system in MISSION_REQUEST")
4283
if m.target_component != self.mav.mav.srcComponent:
4284
raise NotAchievedException("Incorrect target component in MISSION_REQUEST")
4285
tstart = self.get_sim_time()
4286
rerequest_count = 0
4287
received_text = False
4288
received_ack = False
4289
while True:
4290
if received_ack and received_text:
4291
break
4292
if self.get_sim_time_cached() - tstart > 10:
4293
raise NotAchievedException("Did not get expected ack and statustext")
4294
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK', 'STATUSTEXT'],
4295
blocking=True,
4296
timeout=1)
4297
self.progress("Got (%s)" % str(m))
4298
if m is None:
4299
self.progress("Did not receive any messages")
4300
continue
4301
if m.get_type() == "MISSION_REQUEST":
4302
if m.seq != 0:
4303
raise NotAchievedException("Received request for invalid seq")
4304
if m.target_system != self.mav.mav.srcSystem:
4305
raise NotAchievedException("Incorrect target system in MISSION_REQUEST")
4306
if m.target_component != self.mav.mav.srcComponent:
4307
raise NotAchievedException("Incorrect target component in MISSION_REQUEST")
4308
rerequest_count += 1
4309
self.progress("Valid re-request received.")
4310
continue
4311
if m.get_type() == "MISSION_ACK":
4312
if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE:
4313
raise NotAchievedException("Wrong mission type")
4314
if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:
4315
raise NotAchievedException("Wrong result")
4316
received_ack = True
4317
continue
4318
if m.get_type() == "STATUSTEXT":
4319
if "upload time" in m.text:
4320
received_text = True
4321
continue
4322
if rerequest_count < 3:
4323
raise NotAchievedException("Expected several re-requests of mission item")
4324
self.end_subtest("fence upload timeouts 1")
4325
4326
def expect_request_for_item(self, item):
4327
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],
4328
blocking=True,
4329
timeout=1)
4330
self.progress("Got (%s)" % str(m))
4331
if m is None:
4332
raise NotAchievedException("Did not get ACK or mission request")
4333
4334
if m.get_type() == "MISSION_ACK":
4335
raise NotAchievedException("Expected MISSION_REQUEST")
4336
4337
if m.seq != item.seq:
4338
raise NotAchievedException("Expected request for seq=%u" % item.seq)
4339
4340
if m.target_system != self.mav.mav.srcSystem:
4341
raise NotAchievedException("Incorrect target system in MISSION_REQUEST")
4342
if m.target_component != self.mav.mav.srcComponent:
4343
raise NotAchievedException("Incorrect target component in MISSION_REQUEST")
4344
4345
def test_fence_upload_timeouts_2(self, target_system=1, target_component=1):
4346
self.start_subtest("fence upload timeouts 2")
4347
self.progress("Telling victim there will be two items coming")
4348
# avoid a timeout race condition where ArduPilot re-requests a
4349
# fence point before we receive and respond to the first one.
4350
# Since ArduPilot has a 1s timeout on re-requesting, This only
4351
# requires a round-trip delay of 1/speedup seconds to trigger
4352
# - and that has been seen in practise on Travis
4353
old_speedup = self.get_parameter("SIM_SPEEDUP")
4354
self.set_parameter("SIM_SPEEDUP", 1)
4355
self.mav.mav.mission_count_send(target_system,
4356
target_component,
4357
2,
4358
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4359
self.progress("Sending item with seq=0")
4360
item = self.mav.mav.mission_item_int_encode(
4361
target_system,
4362
target_component,
4363
0, # seq
4364
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4365
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
4366
0, # current
4367
0, # autocontinue
4368
1, # p1 radius
4369
0, # p2
4370
0, # p3
4371
0, # p4
4372
int(1.1 * 1e7), # latitude
4373
int(1.2 * 1e7), # longitude
4374
33.0000, # altitude
4375
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4376
self.expect_request_for_item(item)
4377
item.pack(self.mav.mav)
4378
self.mav.mav.send(item)
4379
4380
self.progress("Sending item with seq=1")
4381
item = self.mav.mav.mission_item_int_encode(
4382
target_system,
4383
target_component,
4384
1, # seq
4385
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
4386
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
4387
0, # current
4388
0, # autocontinue
4389
1, # p1 radius
4390
0, # p2
4391
0, # p3
4392
0, # p4
4393
int(1.1 * 1e7), # latitude
4394
int(1.2 * 1e7), # longitude
4395
33.0000, # altitude
4396
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4397
4398
self.expect_request_for_item(item)
4399
4400
self.set_parameter("SIM_SPEEDUP", old_speedup)
4401
4402
self.progress("Now waiting for a timeout")
4403
tstart = self.get_sim_time()
4404
rerequest_count = 0
4405
received_text = False
4406
received_ack = False
4407
while True:
4408
if received_ack and received_text:
4409
break
4410
if self.get_sim_time_cached() - tstart > 10:
4411
raise NotAchievedException("Did not get expected ack and statustext")
4412
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK', 'STATUSTEXT'],
4413
blocking=True,
4414
timeout=0.1)
4415
self.progress("Got (%s)" % str(m))
4416
if m is None:
4417
self.progress("Did not receive any messages")
4418
continue
4419
if m.get_type() == "MISSION_REQUEST":
4420
if m.seq != 1:
4421
raise NotAchievedException("Received request for invalid seq")
4422
if m.target_system != self.mav.mav.srcSystem:
4423
raise NotAchievedException("Incorrect target system in MISSION_REQUEST")
4424
if m.target_component != self.mav.mav.srcComponent:
4425
raise NotAchievedException("Incorrect target component in MISSION_REQUEST")
4426
rerequest_count += 1
4427
self.progress("Valid re-request received.")
4428
continue
4429
if m.get_type() == "MISSION_ACK":
4430
if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE:
4431
raise NotAchievedException("Wrong mission type")
4432
if m.type != mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED:
4433
raise NotAchievedException("Wrong result")
4434
received_ack = True
4435
continue
4436
if m.get_type() == "STATUSTEXT":
4437
if "upload time" in m.text:
4438
received_text = True
4439
continue
4440
if rerequest_count < 3:
4441
raise NotAchievedException("Expected several re-requests of mission item")
4442
self.end_subtest("fence upload timeouts 2")
4443
4444
def test_fence_upload_timeouts(self, target_system=1, target_component=1):
4445
self.test_fence_upload_timeouts_1(target_system=target_system,
4446
target_component=target_component)
4447
self.test_fence_upload_timeouts_2(target_system=target_system,
4448
target_component=target_component)
4449
4450
def test_poly_fence_compatability_ordering(self, target_system=1, target_component=1):
4451
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4452
target_system=target_system,
4453
target_component=target_component)
4454
here = self.mav.location()
4455
self.progress("try uploading return point last")
4456
self.roundtrip_fence_using_fencepoint_protocol([
4457
self.offset_location_ne(here, 0, 0), # bl // return point
4458
self.offset_location_ne(here, -50, 20), # bl
4459
self.offset_location_ne(here, 50, 20), # br
4460
self.offset_location_ne(here, 50, 40), # tr
4461
self.offset_location_ne(here, -50, 40), # tl,
4462
self.offset_location_ne(here, -50, 20), # closing point
4463
], ordering=[1, 2, 3, 4, 5, 0])
4464
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4465
target_system=target_system,
4466
target_component=target_component)
4467
4468
self.progress("try uploading return point in middle")
4469
self.roundtrip_fence_using_fencepoint_protocol([
4470
self.offset_location_ne(here, 0, 0), # bl // return point
4471
self.offset_location_ne(here, -50, 20), # bl
4472
self.offset_location_ne(here, 50, 20), # br
4473
self.offset_location_ne(here, 50, 40), # tr
4474
self.offset_location_ne(here, -50, 40), # tl,
4475
self.offset_location_ne(here, -50, 20), # closing point
4476
], ordering=[1, 2, 3, 0, 4, 5])
4477
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4478
target_system=target_system,
4479
target_component=target_component)
4480
4481
self.progress("try closing point in middle")
4482
self.roundtrip_fence_using_fencepoint_protocol([
4483
self.offset_location_ne(here, 0, 0), # bl // return point
4484
self.offset_location_ne(here, -50, 20), # bl
4485
self.offset_location_ne(here, 50, 20), # br
4486
self.offset_location_ne(here, 50, 40), # tr
4487
self.offset_location_ne(here, -50, 40), # tl,
4488
self.offset_location_ne(here, -50, 20), # closing point
4489
], ordering=[0, 1, 2, 5, 3, 4])
4490
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4491
target_system=target_system,
4492
target_component=target_component)
4493
4494
# this is expected to fail as we don't return the closing
4495
# point correctly until the first is uploaded
4496
# self.progress("try closing point first")
4497
# failed = False
4498
# try:
4499
# self.roundtrip_fence_using_fencepoint_protocol([
4500
# self.offset_location_ne(here, 0, 0), # bl // return point
4501
# self.offset_location_ne(here, -50, 20), # bl
4502
# self.offset_location_ne(here, 50, 20), # br
4503
# self.offset_location_ne(here, 50, 40), # tr
4504
# self.offset_location_ne(here, -50, 40), # tl,
4505
# self.offset_location_ne(here, -50, 20), # closing point
4506
# ], ordering=[5, 0, 1, 2, 3, 4])
4507
# except NotAchievedException as e:
4508
# failed = "got=0.000000 want=" in str(e)
4509
# if not failed:
4510
# raise NotAchievedException("Expected failure, did not get it")
4511
# self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4512
# target_system=target_system,
4513
# target_component=target_component)
4514
4515
self.progress("try (almost) reverse order")
4516
self.roundtrip_fence_using_fencepoint_protocol([
4517
self.offset_location_ne(here, 0, 0), # bl // return point
4518
self.offset_location_ne(here, -50, 20), # bl
4519
self.offset_location_ne(here, 50, 20), # br
4520
self.offset_location_ne(here, 50, 40), # tr
4521
self.offset_location_ne(here, -50, 40), # tl,
4522
self.offset_location_ne(here, -50, 20), # closing point
4523
], ordering=[4, 3, 2, 1, 0, 5])
4524
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4525
target_system=target_system,
4526
target_component=target_component)
4527
4528
def test_poly_fence_big_then_small(self, target_system=1, target_component=1):
4529
here = self.mav.location()
4530
4531
self.roundtrip_fence_using_fencepoint_protocol([
4532
self.offset_location_ne(here, 0, 0), # bl // return point
4533
self.offset_location_ne(here, -50, 20), # bl
4534
self.offset_location_ne(here, 50, 20), # br
4535
self.offset_location_ne(here, 50, 40), # tr
4536
self.offset_location_ne(here, -50, 40), # tl,
4537
self.offset_location_ne(here, -50, 20), # closing point
4538
], ordering=[1, 2, 3, 4, 5, 0])
4539
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4540
if len(downloaded_items) != 5:
4541
# that's one return point and then bl, br, tr, then tl
4542
raise NotAchievedException("Bad number of downloaded items in original download")
4543
4544
self.roundtrip_fence_using_fencepoint_protocol([
4545
self.offset_location_ne(here, 0, 0), # bl // return point
4546
self.offset_location_ne(here, -50, 20), # bl
4547
self.offset_location_ne(here, 50, 40), # tr
4548
self.offset_location_ne(here, -50, 40), # tl,
4549
self.offset_location_ne(here, -50, 20), # closing point
4550
], ordering=[1, 2, 3, 4, 0])
4551
4552
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4553
want_count = 4
4554
if len(downloaded_items) != want_count:
4555
# that's one return point and then bl, tr, then tl
4556
raise NotAchievedException("Bad number of downloaded items in second download got=%u wanted=%u" %
4557
(len(downloaded_items), want_count))
4558
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4559
if len(downloaded_items) != 4:
4560
# that's one return point and then bl, tr, then tl
4561
raise NotAchievedException("Bad number of downloaded items in second download (second time) got=%u want=%u" %
4562
(len(downloaded_items), want_count))
4563
4564
def test_poly_fence_compatability(self, target_system=1, target_component=1):
4565
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
4566
target_system=target_system,
4567
target_component=target_component)
4568
4569
self.test_poly_fence_compatability_ordering(target_system=target_system, target_component=target_component)
4570
4571
here = self.mav.location()
4572
4573
self.progress("Playing with changing point count")
4574
self.roundtrip_fence_using_fencepoint_protocol(
4575
[
4576
self.offset_location_ne(here, 0, 0), # bl // return point
4577
self.offset_location_ne(here, -50, 20), # bl
4578
self.offset_location_ne(here, 50, 20), # br
4579
self.offset_location_ne(here, 50, 40), # tr
4580
self.offset_location_ne(here, -50, 40), # tl,
4581
self.offset_location_ne(here, -50, 20), # closing point
4582
])
4583
self.roundtrip_fence_using_fencepoint_protocol(
4584
[
4585
self.offset_location_ne(here, 0, 0), # bl // return point
4586
self.offset_location_ne(here, -50, 20), # bl
4587
self.offset_location_ne(here, 50, 20), # br
4588
self.offset_location_ne(here, -50, 40), # tl,
4589
self.offset_location_ne(here, -50, 20), # closing point
4590
])
4591
self.roundtrip_fence_using_fencepoint_protocol(
4592
[
4593
self.offset_location_ne(here, 0, 0), # bl // return point
4594
self.offset_location_ne(here, -50, 20), # bl
4595
self.offset_location_ne(here, 50, 20), # br
4596
self.offset_location_ne(here, 50, 40), # tr
4597
self.offset_location_ne(here, -50, 40), # tl,
4598
self.offset_location_ne(here, -50, 20), # closing point
4599
])
4600
4601
def test_poly_fence_reboot_survivability(self):
4602
here = self.mav.location()
4603
4604
self.upload_fences_from_locations([
4605
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4606
# east
4607
self.offset_location_ne(here, -50, 20), # bl
4608
self.offset_location_ne(here, 50, 20), # br
4609
self.offset_location_ne(here, 50, 40), # tr
4610
self.offset_location_ne(here, -50, 40), # tl,
4611
]),
4612
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4613
# over the top of the vehicle
4614
self.offset_location_ne(here, -50, -50), # bl
4615
self.offset_location_ne(here, -50, 50), # br
4616
self.offset_location_ne(here, 50, 50), # tr
4617
self.offset_location_ne(here, 50, -50), # tl,
4618
]),
4619
])
4620
self.reboot_sitl()
4621
downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
4622
downloaded_len = len(downloaded_items)
4623
if downloaded_len != 8:
4624
raise NotAchievedException("Items did not survive reboot (want=%u got=%u)" %
4625
(8, downloaded_len))
4626
4627
def PolyFence(self):
4628
'''test fence-related functions'''
4629
target_system = 1
4630
target_component = 1
4631
4632
self.change_mode("LOITER")
4633
self.wait_ready_to_arm()
4634
here = self.mav.location()
4635
self.progress("here: %f %f" % (here.lat, here.lng))
4636
self.set_parameters({
4637
"FENCE_ENABLE": 1,
4638
"AVOID_ENABLE": 0,
4639
})
4640
4641
# self.set_parameter("SIM_SPEEDUP", 1)
4642
4643
self.test_poly_fence_big_then_small()
4644
4645
self.test_poly_fence_compatability()
4646
4647
self.test_fence_upload_timeouts()
4648
4649
self.test_poly_fence_noarms(target_system=target_system, target_component=target_component)
4650
4651
self.arm_vehicle()
4652
4653
self.test_poly_fence_inclusion(here, target_system=target_system, target_component=target_component)
4654
self.test_poly_fence_exclusion(here, target_system=target_system, target_component=target_component)
4655
4656
self.disarm_vehicle()
4657
4658
self.test_poly_fence_reboot_survivability()
4659
4660
def test_poly_fence_inclusion_overlapping_inclusion_circles(self, here, target_system=1, target_component=1):
4661
self.start_subtest("Overlapping circular inclusion")
4662
self.upload_fences_from_locations([
4663
(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {
4664
"radius": 30,
4665
"loc": self.offset_location_ne(here, -20, 0),
4666
}),
4667
(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {
4668
"radius": 30,
4669
"loc": self.offset_location_ne(here, 20, 0),
4670
}),
4671
])
4672
if self.mavproxy is not None:
4673
# handy for getting pretty pictures
4674
self.mavproxy.send("fence list\n")
4675
4676
self.delay_sim_time(5)
4677
self.progress("Drive outside top circle")
4678
fence_middle = self.offset_location_ne(here, -150, 0)
4679
self.drive_somewhere_breach_boundary_and_rtl(
4680
fence_middle,
4681
target_system=target_system,
4682
target_component=target_component)
4683
4684
self.delay_sim_time(5)
4685
self.progress("Drive outside bottom circle")
4686
fence_middle = self.offset_location_ne(here, 150, 0)
4687
self.drive_somewhere_breach_boundary_and_rtl(
4688
fence_middle,
4689
target_system=target_system,
4690
target_component=target_component)
4691
4692
def test_poly_fence_inclusion(self, here, target_system=1, target_component=1):
4693
self.progress("Circle and Polygon inclusion")
4694
self.test_poly_fence_inclusion_overlapping_inclusion_circles(
4695
here,
4696
target_system=target_system,
4697
target_component=target_component)
4698
4699
self.upload_fences_from_locations([
4700
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
4701
self.offset_location_ne(here, -40, -20), # tl
4702
self.offset_location_ne(here, 50, -20), # tr
4703
self.offset_location_ne(here, 50, 20), # br
4704
self.offset_location_ne(here, -40, 20), # bl,
4705
]),
4706
(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {
4707
"radius": 30,
4708
"loc": self.offset_location_ne(here, -20, 0),
4709
}),
4710
])
4711
4712
self.delay_sim_time(5)
4713
if self.mavproxy is not None:
4714
self.mavproxy.send("fence list\n")
4715
self.progress("Drive outside polygon")
4716
fence_middle = self.offset_location_ne(here, -150, 0)
4717
self.drive_somewhere_breach_boundary_and_rtl(
4718
fence_middle,
4719
target_system=target_system,
4720
target_component=target_component)
4721
4722
self.delay_sim_time(5)
4723
self.progress("Drive outside circle")
4724
fence_middle = self.offset_location_ne(here, 150, 0)
4725
self.drive_somewhere_breach_boundary_and_rtl(
4726
fence_middle,
4727
target_system=target_system,
4728
target_component=target_component)
4729
4730
self.upload_fences_from_locations([
4731
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
4732
self.offset_location_ne(here, -20, -25), # tl
4733
self.offset_location_ne(here, 50, -25), # tr
4734
self.offset_location_ne(here, 50, 15), # br
4735
self.offset_location_ne(here, -20, 15), # bl,
4736
]),
4737
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
4738
self.offset_location_ne(here, 20, -20), # tl
4739
self.offset_location_ne(here, -50, -20), # tr
4740
self.offset_location_ne(here, -50, 20), # br
4741
self.offset_location_ne(here, 20, 20), # bl,
4742
]),
4743
])
4744
4745
self.delay_sim_time(5)
4746
if self.mavproxy is not None:
4747
self.mavproxy.send("fence list\n")
4748
self.progress("Drive outside top polygon")
4749
fence_middle = self.offset_location_ne(here, -150, 0)
4750
self.drive_somewhere_breach_boundary_and_rtl(
4751
fence_middle,
4752
target_system=target_system,
4753
target_component=target_component)
4754
4755
self.delay_sim_time(5)
4756
self.progress("Drive outside bottom polygon")
4757
fence_middle = self.offset_location_ne(here, 150, 0)
4758
self.drive_somewhere_breach_boundary_and_rtl(
4759
fence_middle,
4760
target_system=target_system,
4761
target_component=target_component)
4762
4763
def test_poly_fence_exclusion(self, here, target_system=1, target_component=1):
4764
4765
self.upload_fences_from_locations([
4766
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4767
# east
4768
self.offset_location_ne(here, -50, 20), # bl
4769
self.offset_location_ne(here, 50, 20), # br
4770
self.offset_location_ne(here, 50, 40), # tr
4771
self.offset_location_ne(here, -50, 40), # tl,
4772
]),
4773
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4774
# west
4775
self.offset_location_ne(here, -50, -20), # tl
4776
self.offset_location_ne(here, 50, -20), # tr
4777
self.offset_location_ne(here, 50, -40), # br
4778
self.offset_location_ne(here, -50, -40), # bl,
4779
]),
4780
(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION, {
4781
"radius": 30,
4782
"loc": self.offset_location_ne(here, -60, 0),
4783
}),
4784
])
4785
self.delay_sim_time(5)
4786
if self.mavproxy is not None:
4787
self.mavproxy.send("fence list\n")
4788
4789
self.progress("Breach eastern boundary")
4790
fence_middle = self.offset_location_ne(here, 0, 30)
4791
self.drive_somewhere_breach_boundary_and_rtl(fence_middle,
4792
target_system=target_system,
4793
target_component=target_component)
4794
4795
self.progress("delaying - hack to work around manual recovery bug")
4796
self.delay_sim_time(5)
4797
4798
self.progress("Breach western boundary")
4799
fence_middle = self.offset_location_ne(here, 0, -30)
4800
self.drive_somewhere_breach_boundary_and_rtl(fence_middle,
4801
target_system=target_system,
4802
target_component=target_component)
4803
4804
self.progress("delaying - hack to work around manual recovery bug")
4805
self.delay_sim_time(5)
4806
4807
self.progress("Breach southern circle")
4808
fence_middle = self.offset_location_ne(here, -150, 0)
4809
self.drive_somewhere_breach_boundary_and_rtl(fence_middle,
4810
target_system=target_system,
4811
target_component=target_component)
4812
4813
def SmartRTL(self):
4814
'''Test SmartRTL'''
4815
self.change_mode("STEERING")
4816
self.wait_ready_to_arm()
4817
self.arm_vehicle()
4818
# drive two sides of a square, make sure we don't go back through
4819
# the middle of the square
4820
self.progress("Driving North")
4821
self.reach_heading_manual(0)
4822
self.set_rc(3, 2000)
4823
self.delay_sim_time(5)
4824
self.set_rc(3, 1000)
4825
self.wait_groundspeed(0, 1)
4826
loc = self.mav.location()
4827
self.progress("Driving East")
4828
self.set_rc(3, 2000)
4829
self.reach_heading_manual(90)
4830
self.set_rc(3, 2000)
4831
self.delay_sim_time(5)
4832
self.set_rc(3, 1000)
4833
4834
self.progress("Entering smartrtl")
4835
self.change_mode("SMART_RTL")
4836
4837
self.progress("Ensure we go via intermediate point")
4838
self.wait_distance_to_location(loc, 0, 5, timeout=60)
4839
4840
self.progress("Ensure we get home")
4841
self.wait_distance_to_home(3, 7, timeout=30)
4842
4843
self.disarm_vehicle()
4844
4845
def MotorTest(self):
4846
'''Motor Test triggered via mavlink'''
4847
magic_throttle_value = 1812
4848
self.wait_ready_to_arm()
4849
self.run_cmd(
4850
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
4851
p1=1, # motor instance
4852
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, # throttle type
4853
p3=magic_throttle_value, # throttle
4854
p4=5, # timeout
4855
p5=1, # motor count
4856
p6=0, # test order (see MOTOR_TEST_ORDER)
4857
)
4858
self.wait_armed()
4859
self.progress("Waiting for magic throttle value")
4860
self.wait_servo_channel_value(3, magic_throttle_value)
4861
self.wait_servo_channel_value(3, self.get_parameter("RC3_TRIM", 5), timeout=10)
4862
self.wait_disarmed()
4863
4864
def PolyFenceObjectAvoidanceGuided(self, target_system=1, target_component=1):
4865
'''PolyFence object avoidance tests - guided mode'''
4866
if not self.mavproxy_can_do_mision_item_protocols():
4867
return
4868
4869
self.test_poly_fence_object_avoidance_guided_pathfinding(
4870
target_system=target_system,
4871
target_component=target_component)
4872
self.test_poly_fence_object_avoidance_guided_two_squares(
4873
target_system=target_system,
4874
target_component=target_component)
4875
4876
def PolyFenceObjectAvoidanceAuto(self, target_system=1, target_component=1):
4877
'''PolyFence object avoidance tests - auto mode'''
4878
mavproxy = self.start_mavproxy()
4879
self.load_fence_using_mavproxy(mavproxy, "rover-path-planning-fence.txt")
4880
self.stop_mavproxy(mavproxy)
4881
# self.load_fence("rover-path-planning-fence.txt")
4882
self.load_mission("rover-path-planning-mission.txt")
4883
self.set_parameters({
4884
"AVOID_ENABLE": 3,
4885
"OA_TYPE": 2,
4886
"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
4887
})
4888
self.reboot_sitl()
4889
self.change_mode('AUTO')
4890
self.wait_ready_to_arm()
4891
self.arm_vehicle()
4892
self.set_parameter("FENCE_ENABLE", 1)
4893
# target_loc is copied from the mission file
4894
target_loc = mavutil.location(40.073799, -105.229156)
4895
self.wait_location(target_loc, height_accuracy=None, timeout=300)
4896
# mission has RTL as last item
4897
self.wait_distance_to_home(3, 7, timeout=300)
4898
self.disarm_vehicle()
4899
4900
def send_guided_mission_item(self, loc, target_system=1, target_component=1):
4901
self.mav.mav.mission_item_send(
4902
target_system,
4903
target_component,
4904
0,
4905
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
4906
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
4907
2, # current
4908
0, # autocontinue
4909
0, # param1
4910
0, # param2
4911
0, # param3
4912
0, # param4
4913
loc.lat, # x
4914
loc.lng, # y
4915
0 # z
4916
)
4917
4918
def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, target_component=1):
4919
self.load_fence("rover-path-planning-fence.txt")
4920
self.set_parameters({
4921
"AVOID_ENABLE": 3,
4922
"OA_TYPE": 2,
4923
"FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601
4924
})
4925
self.reboot_sitl()
4926
self.change_mode('GUIDED')
4927
self.wait_ready_to_arm()
4928
self.arm_vehicle()
4929
self.set_parameter("FENCE_ENABLE", 1)
4930
target_loc = mavutil.location(40.073800, -105.229172)
4931
self.send_guided_mission_item(target_loc,
4932
target_system=target_system,
4933
target_component=target_component)
4934
self.wait_location(target_loc, timeout=300)
4935
self.do_RTL(timeout=300)
4936
self.disarm_vehicle()
4937
4938
def WheelEncoders(self):
4939
'''make sure wheel encoders are generally working'''
4940
self.set_parameters({
4941
"WENC_TYPE": 10,
4942
"EK3_ENABLE": 1,
4943
"AHRS_EKF_TYPE": 3,
4944
})
4945
self.reboot_sitl()
4946
self.change_mode("LOITER")
4947
self.wait_ready_to_arm()
4948
self.change_mode("MANUAL")
4949
self.arm_vehicle()
4950
self.set_rc(3, 1600)
4951
4952
m = self.assert_receive_message('WHEEL_DISTANCE', timeout=5)
4953
4954
tstart = self.get_sim_time()
4955
while True:
4956
if self.get_sim_time_cached() - tstart > 10:
4957
break
4958
dist_home = self.distance_to_home(use_cached_home=True)
4959
m = self.mav.messages.get("WHEEL_DISTANCE")
4960
delta = abs(m.distance[0] - dist_home)
4961
self.progress("dist-home=%f wheel-distance=%f delta=%f" %
4962
(dist_home, m.distance[0], delta))
4963
if delta > 5:
4964
raise NotAchievedException("wheel distance incorrect")
4965
self.disarm_vehicle()
4966
4967
def test_poly_fence_object_avoidance_guided_two_squares(self, target_system=1, target_component=1):
4968
self.start_subtest("Ensure we can steer around obstacles in guided mode")
4969
here = self.mav.location()
4970
self.upload_fences_from_locations([
4971
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4972
# east
4973
self.offset_location_ne(here, -50, 20), # bl
4974
self.offset_location_ne(here, 50, 10), # tl
4975
self.offset_location_ne(here, 50, 30), # tr
4976
self.offset_location_ne(here, -50, 40), # br,
4977
]),
4978
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
4979
# further east (and south
4980
self.offset_location_ne(here, -60, 60), # bl
4981
self.offset_location_ne(here, 40, 70), # tl
4982
self.offset_location_ne(here, 40, 90), # tr
4983
self.offset_location_ne(here, -60, 80), # br,
4984
]),
4985
])
4986
if self.mavproxy is not None:
4987
self.mavproxy.send("fence list\n")
4988
self.context_push()
4989
ex = None
4990
try:
4991
self.set_parameters({
4992
"AVOID_ENABLE": 3,
4993
"OA_TYPE": 2,
4994
})
4995
self.reboot_sitl()
4996
self.change_mode('GUIDED')
4997
self.wait_ready_to_arm()
4998
self.set_parameter("FENCE_ENABLE", 1)
4999
if self.mavproxy is not None:
5000
self.mavproxy.send("fence list\n")
5001
self.arm_vehicle()
5002
5003
self.change_mode("GUIDED")
5004
target = mavutil.location(40.071382, -105.228340, 0, 0)
5005
self.send_guided_mission_item(target,
5006
target_system=target_system,
5007
target_component=target_component)
5008
self.wait_location(target, timeout=300)
5009
self.do_RTL()
5010
self.disarm_vehicle()
5011
except Exception as e:
5012
self.print_exception_caught(e)
5013
ex = e
5014
self.context_pop()
5015
self.reboot_sitl()
5016
if ex is not None:
5017
raise ex
5018
5019
def test_poly_fence_avoidance_dont_breach_exclusion(self, target_system=1, target_component=1):
5020
self.start_subtest("Ensure we stop before breaching an exclusion fence")
5021
here = self.mav.location()
5022
self.upload_fences_from_locations([
5023
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
5024
# east
5025
self.offset_location_ne(here, -50, 20), # bl
5026
self.offset_location_ne(here, 50, 20), # br
5027
self.offset_location_ne(here, 50, 40), # tr
5028
self.offset_location_ne(here, -50, 40), # tl,
5029
]),
5030
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
5031
# west
5032
self.offset_location_ne(here, -50, -20), # tl
5033
self.offset_location_ne(here, 50, -20), # tr
5034
self.offset_location_ne(here, 50, -40), # br
5035
self.offset_location_ne(here, -50, -40), # bl,
5036
]),
5037
(mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION, {
5038
"radius": 30,
5039
"loc": self.offset_location_ne(here, -60, 0),
5040
}),
5041
])
5042
if self.mavproxy is not None:
5043
self.mavproxy.send("fence list\n")
5044
self.set_parameters({
5045
"FENCE_ENABLE": 1,
5046
"AVOID_ENABLE": 3,
5047
})
5048
fence_middle = self.offset_location_ne(here, 0, 30)
5049
# FIXME: this might be nowhere near "here"!
5050
expected_stopping_point = mavutil.location(40.0713376, -105.2295738, 0, 0)
5051
self.drive_somewhere_stop_at_boundary(
5052
fence_middle,
5053
expected_stopping_point,
5054
target_system=target_system,
5055
target_component=target_component,
5056
expected_distance_epsilon=3)
5057
self.set_parameter("AVOID_ENABLE", 0)
5058
self.do_RTL()
5059
5060
def do_RTL(self, distance_min=3, distance_max=7, timeout=60):
5061
self.change_mode("RTL")
5062
self.wait_distance_to_home(distance_min, distance_max, timeout=timeout)
5063
5064
def PolyFenceAvoidance(self, target_system=1, target_component=1):
5065
'''PolyFence avoidance tests'''
5066
self.change_mode("LOITER")
5067
self.wait_ready_to_arm()
5068
self.arm_vehicle()
5069
self.change_mode("MANUAL")
5070
self.reach_heading_manual(180, turn_right=False)
5071
self.change_mode("GUIDED")
5072
5073
self.test_poly_fence_avoidance_dont_breach_exclusion(target_system=target_system, target_component=target_component)
5074
5075
self.disarm_vehicle()
5076
5077
def PolyFenceObjectAvoidanceBendyRuler(self, target_system=1, target_component=1):
5078
'''PolyFence object avoidance tests - bendy ruler'''
5079
self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")
5080
self.set_parameters({
5081
"AVOID_ENABLE": 3,
5082
"OA_TYPE": 1,
5083
"FENCE_ENABLE": 1,
5084
"WP_RADIUS": 5,
5085
})
5086
self.reboot_sitl()
5087
self.set_parameters({
5088
"OA_BR_LOOKAHEAD": 50,
5089
})
5090
self.change_mode('GUIDED')
5091
self.wait_ready_to_arm()
5092
self.arm_vehicle()
5093
target_loc = mavutil.location(40.071060, -105.227734, 1584, 0)
5094
self.send_guided_mission_item(target_loc,
5095
target_system=target_system,
5096
target_component=target_component)
5097
# FIXME: we don't get within WP_RADIUS of our target?!
5098
self.wait_location(target_loc, timeout=300, accuracy=15)
5099
self.do_RTL(timeout=300)
5100
self.disarm_vehicle()
5101
5102
def PolyFenceObjectAvoidanceBendyRulerEasierGuided(self, target_system=1, target_component=1):
5103
'''finish-line issue means we can't complete the harder one. This
5104
test can go away once we've nailed that one. The only
5105
difference here is the target point.
5106
'''
5107
self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")
5108
self.set_parameters({
5109
"AVOID_ENABLE": 3,
5110
"OA_TYPE": 1,
5111
"FENCE_ENABLE": 1,
5112
"WP_RADIUS": 5,
5113
})
5114
self.reboot_sitl()
5115
self.set_parameters({
5116
"OA_BR_LOOKAHEAD": 60,
5117
})
5118
self.change_mode('GUIDED')
5119
self.wait_ready_to_arm()
5120
self.arm_vehicle()
5121
target_loc = mavutil.location(40.071260, -105.227000, 1584, 0)
5122
self.send_guided_mission_item(target_loc,
5123
target_system=target_system,
5124
target_component=target_component)
5125
# FIXME: we don't get within WP_RADIUS of our target?!
5126
self.wait_location(target_loc, timeout=300, accuracy=15)
5127
self.do_RTL(timeout=300)
5128
self.disarm_vehicle()
5129
5130
def PolyFenceObjectAvoidanceBendyRulerEasierAuto(self, target_system=1, target_component=1):
5131
'''finish-line issue means we can't complete the harder one. This
5132
test can go away once we've nailed that one. The only
5133
difference here is the target point.
5134
'''
5135
self.load_fence_using_mavwp("rover-path-bendyruler-fence.txt")
5136
self.load_mission("rover-path-bendyruler-mission-easier.txt")
5137
5138
self.set_parameters({
5139
"AVOID_ENABLE": 3,
5140
"OA_TYPE": 1, # BendyRuler
5141
"FENCE_ENABLE": 1,
5142
"WP_RADIUS": 5,
5143
})
5144
self.reboot_sitl()
5145
self.set_parameters({
5146
"OA_BR_LOOKAHEAD": 60,
5147
})
5148
self.change_mode('AUTO')
5149
self.wait_ready_to_arm()
5150
self.arm_vehicle()
5151
target_loc = mavutil.location(40.071260, -105.227000, 1584, 0)
5152
# target_loc is copied from the mission file
5153
self.wait_location(target_loc, timeout=300)
5154
# mission has RTL as last item
5155
self.wait_distance_to_home(3, 7, timeout=300)
5156
self.disarm_vehicle()
5157
5158
def test_scripting_simple_loop(self):
5159
self.start_subtest("Scripting simple loop")
5160
5161
self.context_push()
5162
5163
messages = []
5164
5165
def my_message_hook(mav, message):
5166
if message.get_type() != 'STATUSTEXT':
5167
return
5168
messages.append(message)
5169
5170
self.install_message_hook_context(my_message_hook)
5171
5172
self.set_parameter("SCR_ENABLE", 1)
5173
self.install_example_script_context("simple_loop.lua")
5174
self.reboot_sitl()
5175
self.delay_sim_time(10)
5176
5177
self.context_pop()
5178
self.reboot_sitl()
5179
5180
# check all messages to see if we got our message
5181
count = 0
5182
for m in messages:
5183
if "hello, world" in m.text:
5184
count += 1
5185
self.progress("Got %u hellos" % count)
5186
if count < 3:
5187
raise NotAchievedException("Expected at least three hellos")
5188
5189
def test_scripting_internal_test(self):
5190
self.start_subtest("Scripting internal test")
5191
5192
self.context_push()
5193
5194
self.set_parameters({
5195
"SCR_ENABLE": 1,
5196
"SCR_HEAP_SIZE": 1024000,
5197
"SCR_VM_I_COUNT": 1000000,
5198
})
5199
self.install_test_modules_context()
5200
self.install_mavlink_module_context()
5201
5202
self.install_test_scripts_context([
5203
"scripting_test.lua",
5204
"scripting_require_test_2.lua",
5205
"math.lua",
5206
"strings.lua",
5207
"mavlink_test.lua",
5208
])
5209
5210
self.context_collect('STATUSTEXT')
5211
self.context_collect('NAMED_VALUE_FLOAT')
5212
5213
self.reboot_sitl()
5214
5215
for success_text in [
5216
"Internal tests passed",
5217
"Require test 2 passed",
5218
"Math tests passed",
5219
"String tests passed",
5220
"Received heartbeat from"
5221
]:
5222
self.wait_statustext(success_text, check_context=True)
5223
5224
for success_nvf in [
5225
"test",
5226
]:
5227
self.assert_received_message_field_values("NAMED_VALUE_FLOAT", {
5228
"name": success_nvf,
5229
}, check_context=True)
5230
5231
self.context_pop()
5232
self.reboot_sitl()
5233
5234
def test_scripting_hello_world(self):
5235
self.start_subtest("Scripting hello world")
5236
5237
self.context_push()
5238
self.context_collect("STATUSTEXT")
5239
self.set_parameter("SCR_ENABLE", 1)
5240
self.install_example_script_context("hello_world.lua")
5241
self.reboot_sitl()
5242
5243
self.wait_statustext('hello, world', check_context=True, timeout=30)
5244
5245
self.context_pop()
5246
self.reboot_sitl()
5247
5248
def ScriptingSteeringAndThrottle(self):
5249
'''Scripting test - steering and throttle'''
5250
self.start_subtest("Scripting square")
5251
5252
self.context_push()
5253
self.install_example_script_context("rover-set-steering-and-throttle.lua")
5254
self.set_parameter("SCR_ENABLE", 1)
5255
self.reboot_sitl()
5256
5257
self.wait_ready_to_arm()
5258
self.arm_vehicle()
5259
self.set_rc(6, 2000)
5260
tstart = self.get_sim_time()
5261
while not self.mode_is("HOLD"):
5262
if self.get_sim_time_cached() - tstart > 30:
5263
raise NotAchievedException("Did not move to hold")
5264
m = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=1)
5265
if m is not None:
5266
self.progress("Current speed: %f" % m.groundspeed)
5267
self.disarm_vehicle()
5268
5269
self.context_pop()
5270
self.reboot_sitl()
5271
5272
def test_scripting_auxfunc(self):
5273
self.start_subtest("Scripting aufunc triggering")
5274
5275
self.context_push()
5276
self.context_collect("STATUSTEXT")
5277
self.set_parameters({
5278
"SCR_ENABLE": 1,
5279
"RELAY1_FUNCTION": 1,
5280
"RELAY1_PIN": 1
5281
})
5282
self.install_example_script_context("RCIN_test.lua")
5283
self.reboot_sitl()
5284
5285
self.wait_parameter_value("SIM_PIN_MASK", 121)
5286
self.wait_parameter_value("SIM_PIN_MASK", 123)
5287
self.wait_parameter_value("SIM_PIN_MASK", 121)
5288
5289
self.context_pop()
5290
self.reboot_sitl()
5291
5292
def test_scripting_print_home_and_origin(self):
5293
self.start_subtest("Scripting print home and origin")
5294
5295
self.context_push()
5296
5297
self.set_parameter("SCR_ENABLE", 1)
5298
self.install_example_script_context("ahrs-print-home-and-origin.lua")
5299
self.reboot_sitl()
5300
self.wait_ready_to_arm()
5301
self.wait_statustext("Home - ")
5302
self.wait_statustext("Origin - ")
5303
5304
self.context_pop()
5305
self.reboot_sitl()
5306
5307
def test_scripting_set_home_to_vehicle_location(self):
5308
self.start_subtest("Scripting set home to vehicle location")
5309
5310
self.context_push()
5311
self.set_parameter("SCR_ENABLE", 1)
5312
self.install_example_script_context("ahrs-set-home-to-vehicle-location.lua")
5313
self.reboot_sitl()
5314
5315
self.wait_statustext("Home position reset")
5316
5317
self.context_pop()
5318
self.reboot_sitl()
5319
5320
def test_scripting_serial_loopback(self):
5321
self.start_subtest("Scripting serial loopback test")
5322
5323
self.context_push()
5324
self.context_collect('STATUSTEXT')
5325
self.set_parameters({
5326
"SCR_ENABLE": 1,
5327
"SCR_SDEV_EN": 1,
5328
"SCR_SDEV1_PROTO": 28,
5329
})
5330
self.install_test_script_context("serial_loopback.lua")
5331
self.reboot_sitl()
5332
5333
for success_text in [
5334
"driver -> device good",
5335
"device -> driver good",
5336
]:
5337
self.wait_statustext(success_text, check_context=True)
5338
5339
self.context_pop()
5340
self.reboot_sitl()
5341
5342
def Scripting(self):
5343
'''Scripting test'''
5344
self.test_scripting_set_home_to_vehicle_location()
5345
self.test_scripting_print_home_and_origin()
5346
self.test_scripting_hello_world()
5347
self.test_scripting_simple_loop()
5348
self.test_scripting_internal_test()
5349
self.test_scripting_auxfunc()
5350
self.test_scripting_serial_loopback()
5351
5352
def test_mission_frame(self, frame, target_system=1, target_component=1):
5353
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION,
5354
target_system=target_system,
5355
target_component=target_component)
5356
items = [
5357
# first item is ignored for missions
5358
self.mav.mav.mission_item_int_encode(
5359
target_system,
5360
target_component,
5361
0, # seq
5362
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5363
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5364
0, # current
5365
0, # autocontinue
5366
3, # p1
5367
0, # p2
5368
0, # p3
5369
0, # p4
5370
int(1.0000 * 1e7), # latitude
5371
int(1.0000 * 1e7), # longitude
5372
31.0000, # altitude
5373
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
5374
self.mav.mav.mission_item_int_encode(
5375
target_system,
5376
target_component,
5377
1, # seq
5378
frame,
5379
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5380
0, # current
5381
0, # autocontinue
5382
3, # p1
5383
0, # p2
5384
0, # p3
5385
0, # p4
5386
int(1.0000 * 1e7), # latitude
5387
int(1.0000 * 1e7), # longitude
5388
31.0000, # altitude
5389
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
5390
]
5391
5392
self.check_mission_upload_download(items)
5393
5394
def MissionFrames(self, target_system=1, target_component=1):
5395
'''Upload/Download of items in different frames'''
5396
for frame in (mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT,
5397
mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT,
5398
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
5399
mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
5400
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
5401
mavutil.mavlink.MAV_FRAME_GLOBAL):
5402
self.test_mission_frame(frame,
5403
target_system=1,
5404
target_component=1)
5405
5406
def mavlink_time_boot_ms(self):
5407
'''returns a time suitable for putting into the time_boot_ms entry in mavlink packets'''
5408
return int(time.time() * 1000000)
5409
5410
def mavlink_time_boot_us(self):
5411
'''returns a time suitable for putting into the time_boot_ms entry in mavlink packets'''
5412
return int(time.time() * 1000000000)
5413
5414
def ap_proximity_mav_obstacle_distance_send(self, data):
5415
increment = data.get("increment", 0)
5416
increment_f = data.get("increment_f", 0.0)
5417
max_distance = data["max_distance"]
5418
invalid_distance = max_distance + 1 # per spec
5419
distances = data["distances"][:]
5420
distances.extend([invalid_distance] * (72-len(distances)))
5421
self.mav.mav.obstacle_distance_send(
5422
self.mavlink_time_boot_us(),
5423
mavutil.mavlink.MAV_DISTANCE_SENSOR_LASER,
5424
distances,
5425
increment,
5426
data["min_distance"],
5427
data["max_distance"],
5428
increment_f,
5429
data["angle_offset"],
5430
mavutil.mavlink.MAV_FRAME_BODY_FRD
5431
)
5432
5433
def send_obstacle_distances_expect_distance_sensor_messages(self, obstacle_distances_in, expect_distance_sensor_messages):
5434
self.delay_sim_time(11) # allow obstacles to time out
5435
self.do_timesync_roundtrip()
5436
expect_distance_sensor_messages_copy = expect_distance_sensor_messages[:]
5437
last_sent = 0
5438
while True:
5439
now = self.get_sim_time_cached()
5440
if now - last_sent > 1:
5441
self.progress("Sending")
5442
self.ap_proximity_mav_obstacle_distance_send(obstacle_distances_in)
5443
last_sent = now
5444
m = self.mav.recv_match(type='DISTANCE_SENSOR', blocking=True, timeout=1)
5445
self.progress("Got (%s)" % str(m))
5446
if m is None:
5447
self.delay_sim_time(1)
5448
continue
5449
orientation = m.orientation
5450
found = False
5451
if m.current_distance == m.max_distance:
5452
# ignored
5453
continue
5454
for expected_distance_sensor_message in expect_distance_sensor_messages_copy:
5455
if expected_distance_sensor_message["orientation"] != orientation:
5456
continue
5457
found = True
5458
if not expected_distance_sensor_message.get("__found__", False):
5459
self.progress("Marking message as found")
5460
expected_distance_sensor_message["__found__"] = True
5461
if (m.current_distance - expected_distance_sensor_message["distance"] > 1):
5462
raise NotAchievedException(
5463
"Bad distance for orient=%u want=%u got=%u" %
5464
(orientation, expected_distance_sensor_message["distance"], m.current_distance))
5465
break
5466
if not found:
5467
raise NotAchievedException("Got unexpected DISTANCE_SENSOR message")
5468
all_found = True
5469
for expected_distance_sensor_message in expect_distance_sensor_messages_copy:
5470
if not expected_distance_sensor_message.get("__found__", False):
5471
self.progress("message still not found (orient=%u" % expected_distance_sensor_message["orientation"])
5472
all_found = False
5473
break
5474
if all_found:
5475
self.progress("Have now seen all expected messages")
5476
break
5477
5478
def AP_Proximity_MAV(self):
5479
'''Test MAV proximity backend'''
5480
5481
self.set_parameters({
5482
"PRX1_TYPE": 2, # AP_Proximity_MAV
5483
"OA_TYPE": 2, # dijkstra
5484
"OA_DB_OUTPUT": 3, # send all items
5485
})
5486
self.reboot_sitl()
5487
5488
# 1 laser pointing straight forward:
5489
self.send_obstacle_distances_expect_distance_sensor_messages(
5490
{
5491
"distances": [234],
5492
"increment_f": 10,
5493
"angle_offset": 0.0,
5494
"min_distance": 0,
5495
"max_distance": 1000, # cm
5496
}, [
5497
{"orientation": 0, "distance": 234},
5498
])
5499
5500
# 5 lasers at front of vehicle, spread over 40 degrees:
5501
self.send_obstacle_distances_expect_distance_sensor_messages(
5502
{
5503
"distances": [111, 222, 333, 444, 555],
5504
"increment_f": 10,
5505
"angle_offset": -20.0,
5506
"min_distance": 0,
5507
"max_distance": 1000, # cm
5508
}, [
5509
{"orientation": 0, "distance": 111},
5510
])
5511
5512
# lots of dense readings (e.g. vision camera:
5513
distances = [0] * 72
5514
for i in range(0, 72):
5515
distances[i] = 1000 + 10*abs(36-i)
5516
5517
self.send_obstacle_distances_expect_distance_sensor_messages(
5518
{
5519
"distances": distances,
5520
"increment_f": 90/72.0,
5521
"angle_offset": -45.0,
5522
"min_distance": 0,
5523
"max_distance": 2000, # cm
5524
}, [
5525
{"orientation": 0, "distance": 1000},
5526
{"orientation": 1, "distance": 1190},
5527
{"orientation": 7, "distance": 1190},
5528
])
5529
5530
def SendToComponents(self):
5531
'''Test ArduPilot send_to_components function'''
5532
self.set_parameter("CAM1_TYPE", 5) # Camera with MAVlink trigger
5533
self.reboot_sitl() # needed for CAM1_TYPE to take effect
5534
self.progress("Introducing ourselves to the autopilot as a component")
5535
old_srcSystem = self.mav.mav.srcSystem
5536
self.mav.mav.srcSystem = 1
5537
self.mav.mav.heartbeat_send(
5538
mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
5539
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
5540
0,
5541
0,
5542
0)
5543
5544
self.progress("Sending control message")
5545
self.context_push()
5546
self.context_collect('COMMAND_LONG')
5547
self.mav.mav.digicam_control_send(
5548
1, # target_system
5549
1, # target_component
5550
1, # start or keep it up
5551
1, # zoom_pos
5552
0, # zoom_step
5553
0, # focus_lock
5554
0, # 1 shot or start filming
5555
17, # command id (de-dupe field)
5556
0, # extra_param
5557
0.0, # extra_value
5558
)
5559
self.mav.mav.srcSystem = old_srcSystem
5560
5561
self.assert_received_message_field_values('COMMAND_LONG', {
5562
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
5563
'param6': 17,
5564
}, timeout=2, check_context=True)
5565
self.context_pop()
5566
5567
# test sending via commands:
5568
for run_cmd in self.run_cmd, self.run_cmd_int:
5569
self.progress("Sending control command")
5570
self.context_push()
5571
self.context_collect('COMMAND_LONG')
5572
run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
5573
p1=1, # start or keep it up
5574
p2=1, # zoom_pos
5575
p3=0, # zoom_step
5576
p4=0, # focus_lock
5577
p5=0, # 1 shot or start filming
5578
p6=37, # command id (de-dupe field)
5579
)
5580
5581
self.assert_received_message_field_values('COMMAND_LONG', {
5582
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
5583
'param6': 37,
5584
}, timeout=2, check_context=True)
5585
5586
self.context_pop()
5587
5588
# test sending via commands:
5589
for run_cmd in self.run_cmd, self.run_cmd_int:
5590
self.progress("Sending configure command")
5591
self.context_push()
5592
self.context_collect('COMMAND_LONG')
5593
run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,
5594
p1=1,
5595
p2=1,
5596
p3=0,
5597
p4=0,
5598
p5=12,
5599
p6=37
5600
)
5601
5602
self.assert_received_message_field_values('COMMAND_LONG', {
5603
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE,
5604
'param5': 12,
5605
'param6': 37,
5606
}, timeout=2, check_context=True)
5607
5608
self.context_pop()
5609
5610
self.mav.mav.srcSystem = old_srcSystem
5611
5612
def SkidSteer(self):
5613
'''Check skid-steering'''
5614
model = "rover-skid"
5615
5616
self.customise_SITL_commandline([],
5617
model=model,
5618
defaults_filepath=self.model_defaults_filepath(model))
5619
5620
self.change_mode("MANUAL")
5621
self.wait_ready_to_arm()
5622
self.arm_vehicle()
5623
self.progress("get a known heading to avoid worrying about wrap")
5624
# this is steering-type-two-paddles
5625
self.set_rc(1, 1400)
5626
self.set_rc(3, 1500)
5627
self.wait_heading(90)
5628
self.progress("straighten up")
5629
self.set_rc(1, 1500)
5630
self.set_rc(3, 1500)
5631
self.progress("steer one way")
5632
self.set_rc(1, 1600)
5633
self.set_rc(3, 1400)
5634
self.wait_heading(120)
5635
self.progress("steer the other")
5636
self.set_rc(1, 1400)
5637
self.set_rc(3, 1600)
5638
self.wait_heading(60)
5639
self.zero_throttle()
5640
self.disarm_vehicle()
5641
5642
def SlewRate(self):
5643
"""Test Motor Slew Rate feature."""
5644
self.context_push()
5645
self.change_mode("MANUAL")
5646
self.wait_ready_to_arm()
5647
self.arm_vehicle()
5648
5649
self.start_subtest("Test no slew behavior")
5650
throttle_channel = 3
5651
throttle_max = 2000
5652
self.set_parameter("MOT_SLEWRATE", 0)
5653
self.set_rc(throttle_channel, throttle_max)
5654
tstart = self.get_sim_time()
5655
self.wait_servo_channel_value(throttle_channel, throttle_max)
5656
tstop = self.get_sim_time()
5657
achieved_time = tstop - tstart
5658
self.progress("achieved_time: %0.1fs" % achieved_time)
5659
if achieved_time > 0.5:
5660
raise NotAchievedException("Output response should be instant, got %f" % achieved_time)
5661
self.zero_throttle()
5662
self.wait_groundspeed(0, 0.5) # why do we not stop?!
5663
5664
self.start_subtest("Test 100% slew rate")
5665
self.set_parameter("MOT_SLEWRATE", 100)
5666
self.set_rc(throttle_channel, throttle_max)
5667
tstart = self.get_sim_time()
5668
self.wait_servo_channel_value(throttle_channel, throttle_max)
5669
tstop = self.get_sim_time()
5670
achieved_time = tstop - tstart
5671
self.progress("achieved_time: %0.1fs" % achieved_time)
5672
if achieved_time < 0.9 or achieved_time > 1.1:
5673
raise NotAchievedException("Output response should be 1s, got %f" % achieved_time)
5674
self.zero_throttle()
5675
self.wait_groundspeed(0, 0.5) # why do we not stop?!
5676
5677
self.start_subtest("Test 50% slew rate")
5678
self.set_parameter("MOT_SLEWRATE", 50)
5679
self.set_rc(throttle_channel, throttle_max)
5680
tstart = self.get_sim_time()
5681
self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=10)
5682
tstop = self.get_sim_time()
5683
achieved_time = tstop - tstart
5684
self.progress("achieved_time: %0.1fs" % achieved_time)
5685
if achieved_time < 1.8 or achieved_time > 2.2:
5686
raise NotAchievedException("Output response should be 2s, got %f" % achieved_time)
5687
self.zero_throttle()
5688
self.wait_groundspeed(0, 0.5) # why do we not stop?!
5689
5690
self.start_subtest("Test 25% slew rate")
5691
self.set_parameter("MOT_SLEWRATE", 25)
5692
self.set_rc(throttle_channel, throttle_max)
5693
tstart = self.get_sim_time()
5694
self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=10)
5695
tstop = self.get_sim_time()
5696
achieved_time = tstop - tstart
5697
self.progress("achieved_time: %0.1fs" % achieved_time)
5698
if achieved_time < 3.6 or achieved_time > 4.4:
5699
raise NotAchievedException("Output response should be 4s, got %f" % achieved_time)
5700
self.zero_throttle()
5701
self.wait_groundspeed(0, 0.5) # why do we not stop?!
5702
5703
self.start_subtest("Test 10% slew rate")
5704
self.set_parameter("MOT_SLEWRATE", 10)
5705
self.set_rc(throttle_channel, throttle_max)
5706
tstart = self.get_sim_time()
5707
self.wait_servo_channel_value(throttle_channel, throttle_max, timeout=20)
5708
tstop = self.get_sim_time()
5709
achieved_time = tstop - tstart
5710
self.progress("achieved_time: %0.1fs" % achieved_time)
5711
if achieved_time < 9 or achieved_time > 11:
5712
raise NotAchievedException("Output response should be 10s, got %f" % achieved_time)
5713
self.zero_throttle()
5714
self.wait_groundspeed(0, 0.5) # why do we not stop?!
5715
self.disarm_vehicle()
5716
self.context_pop()
5717
5718
def SET_ATTITUDE_TARGET(self, target_sysid=None, target_compid=1):
5719
'''Test handling of SET_ATTITUDE_TARGET'''
5720
if target_sysid is None:
5721
target_sysid = self.sysid_thismav()
5722
self.change_mode('GUIDED')
5723
self.wait_ready_to_arm()
5724
self.arm_vehicle()
5725
tstart = self.get_sim_time()
5726
while True:
5727
now = self.get_sim_time_cached()
5728
if now - tstart > 10:
5729
raise AutoTestTimeoutException("Didn't get to speed")
5730
self.mav.mav.set_attitude_target_send(
5731
0, # time_boot_ms
5732
target_sysid,
5733
target_compid,
5734
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |
5735
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE |
5736
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE,
5737
mavextra.euler_to_quat([0,
5738
math.radians(0),
5739
math.radians(0)]), # att
5740
0, # yaw rate (rad/s)
5741
0, # pitch rate
5742
0, # yaw rate
5743
1) # thrust
5744
5745
msg = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=1)
5746
if msg is None:
5747
raise NotAchievedException("No VFR_HUD message")
5748
if msg.groundspeed > 5:
5749
break
5750
self.disarm_vehicle()
5751
5752
def SET_ATTITUDE_TARGET_heading(self, target_sysid=None, target_compid=1):
5753
'''Test handling of SET_ATTITUDE_TARGET'''
5754
self.change_mode('GUIDED')
5755
self.wait_ready_to_arm()
5756
self.arm_vehicle()
5757
5758
for angle in 0, 290, 70, 180, 0:
5759
self.SET_ATTITUDE_TARGET_heading_test_target(angle, target_sysid, target_compid)
5760
self.disarm_vehicle()
5761
5762
def SET_ATTITUDE_TARGET_heading_test_target(self, angle, target_sysid, target_compid):
5763
if target_sysid is None:
5764
target_sysid = self.sysid_thismav()
5765
5766
def poke_set_attitude(value, target):
5767
self.mav.mav.set_attitude_target_send(
5768
0, # time_boot_ms
5769
target_sysid,
5770
target_compid,
5771
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE |
5772
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE |
5773
mavutil.mavlink.ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE,
5774
mavextra.euler_to_quat([
5775
math.radians(0),
5776
math.radians(0),
5777
math.radians(angle)
5778
]), # att
5779
0, # roll rate (rad/s)
5780
0, # pitch rate
5781
0, # yaw rate
5782
1) # thrust
5783
5784
self.wait_heading(angle, called_function=poke_set_attitude, minimum_duration=5)
5785
5786
def SET_POSITION_TARGET_LOCAL_NED(self, target_sysid=None, target_compid=1):
5787
'''Test handling of SET_POSITION_TARGET_LOCAL_NED'''
5788
if target_sysid is None:
5789
target_sysid = self.sysid_thismav()
5790
self.change_mode('GUIDED')
5791
self.wait_ready_to_arm()
5792
self.arm_vehicle()
5793
ofs_x = 30.0
5794
ofs_y = 30.0
5795
5796
def send_target():
5797
self.mav.mav.set_position_target_local_ned_send(
5798
0, # time_boot_ms
5799
target_sysid,
5800
target_compid,
5801
mavutil.mavlink.MAV_FRAME_LOCAL_NED,
5802
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
5803
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
5804
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
5805
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
5806
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
5807
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
5808
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
5809
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
5810
ofs_x, # pos-x
5811
ofs_y, # pos-y
5812
0, # pos-z
5813
0, # vel-x
5814
0, # vel-y
5815
0, # vel-z
5816
0, # acc-x
5817
0, # acc-y
5818
0, # acc-z
5819
0, # yaw
5820
0, # yaw rate
5821
)
5822
5823
self.wait_distance_to_local_position(
5824
(ofs_x, ofs_y, 0),
5825
distance_min=0,
5826
distance_max=3,
5827
timeout=60,
5828
called_function=lambda last_value, target : send_target(),
5829
minimum_duration=5, # make sure we stop!
5830
)
5831
5832
self.do_RTL()
5833
self.disarm_vehicle()
5834
5835
def EndMissionBehavior(self, timeout=60):
5836
'''Test end mission behavior'''
5837
self.context_push()
5838
5839
self.load_mission("end-mission.txt")
5840
self.wait_ready_to_arm()
5841
self.arm_vehicle()
5842
5843
self.start_subtest("Test End Mission Behavior HOLD")
5844
self.context_collect("STATUSTEXT")
5845
self.change_mode("AUTO")
5846
self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)
5847
# On Hold we should just stop and don't update the navigation target anymore
5848
tstart = self.get_sim_time()
5849
while True:
5850
if self.get_sim_time_cached() - tstart > 15:
5851
raise AutoTestTimeoutException("Still getting POSITION_TARGET_GLOBAL_INT")
5852
m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",
5853
blocking=True,
5854
timeout=10)
5855
if m is None:
5856
self.progress("No POSITION_TARGET_GLOBAL_INT received, all good !")
5857
break
5858
self.context_clear_collection("STATUSTEXT")
5859
self.change_mode("GUIDED")
5860
self.context_collect("STATUSTEXT")
5861
5862
self.start_subtest("Test End Mission Behavior LOITER")
5863
self.set_parameter("MIS_DONE_BEHAVE", 1)
5864
self.change_mode("AUTO")
5865
self.wait_text("Mission Complete", check_context=True, wallclock_timeout=2)
5866
# On LOITER we should update the navigation target
5867
tstart = self.get_sim_time()
5868
while True:
5869
if self.get_sim_time_cached() - tstart > 15:
5870
raise AutoTestTimeoutException("Not getting POSITION_TARGET_GLOBAL_INT")
5871
m = self.mav.recv_match(type="POSITION_TARGET_GLOBAL_INT",
5872
blocking=True,
5873
timeout=5)
5874
if m is None:
5875
self.progress("No POSITION_TARGET_GLOBAL_INT received")
5876
continue
5877
else:
5878
if self.get_sim_time_cached() - tstart > 15:
5879
self.progress("Got POSITION_TARGET_GLOBAL_INT, all good !")
5880
break
5881
5882
self.start_subtest("Test End Mission Behavior ACRO")
5883
self.set_parameter("MIS_DONE_BEHAVE", 2)
5884
# race conditions here to do with get_sim_time()
5885
# swallowing heartbeats means we have to be a little
5886
# circuitous when testing here:
5887
self.change_mode("GUIDED")
5888
self.send_cmd_do_set_mode('AUTO')
5889
self.wait_mode("ACRO")
5890
5891
self.start_subtest("Test End Mission Behavior MANUAL")
5892
self.set_parameter("MIS_DONE_BEHAVE", 3)
5893
# race conditions here to do with get_sim_time()
5894
# swallowing heartbeats means we have to be a little
5895
# circuitous when testing here:
5896
self.change_mode("GUIDED")
5897
self.send_cmd_do_set_mode("AUTO")
5898
self.wait_mode("MANUAL")
5899
self.disarm_vehicle()
5900
5901
self.context_pop()
5902
self.reboot_sitl()
5903
5904
def MAVProxyParam(self):
5905
'''Test MAVProxy parameter handling'''
5906
mavproxy = self.start_mavproxy()
5907
mavproxy.send("param fetch\n")
5908
mavproxy.expect("Received [0-9]+ parameters")
5909
self.stop_mavproxy(mavproxy)
5910
5911
def MAV_CMD_DO_SET_MISSION_CURRENT_mission(self, target_system=1, target_component=1):
5912
return copy.copy([
5913
self.mav.mav.mission_item_int_encode(
5914
target_system,
5915
target_component,
5916
0, # seq
5917
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
5918
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5919
0, # current
5920
0, # autocontinue
5921
3, # p1
5922
0, # p2
5923
0, # p3
5924
0, # p4
5925
int(1.0000 * 1e7), # latitude
5926
int(1.0000 * 1e7), # longitude
5927
31.0000, # altitude
5928
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
5929
self.mav.mav.mission_item_int_encode(
5930
target_system,
5931
target_component,
5932
1, # seq
5933
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
5934
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5935
0, # current
5936
0, # autocontinue
5937
3, # p1
5938
0, # p2
5939
0, # p3
5940
0, # p4
5941
int(1.0000 * 1e7), # latitude
5942
int(1.0000 * 1e7), # longitude
5943
31.0000, # altitude
5944
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
5945
self.mav.mav.mission_item_int_encode(
5946
target_system,
5947
target_component,
5948
2, # seq
5949
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
5950
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
5951
0, # current
5952
0, # autocontinue
5953
3, # p1
5954
0, # p2
5955
0, # p3
5956
0, # p4
5957
int(1.0000 * 1e7), # latitude
5958
int(1.0000 * 1e7), # longitude
5959
31.0000, # altitude
5960
mavutil.mavlink.MAV_MISSION_TYPE_MISSION),
5961
])
5962
5963
def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1):
5964
'''Test handling of CMD_DO_SET_MISSION_CURRENT'''
5965
if target_sysid is None:
5966
target_sysid = self.sysid_thismav()
5967
self.check_mission_upload_download(self.MAV_CMD_DO_SET_MISSION_CURRENT_mission())
5968
5969
self.set_current_waypoint(2)
5970
5971
self.set_current_waypoint_using_mav_cmd_do_set_mission_current(2)
5972
5973
self.run_cmd(
5974
mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
5975
p1=17,
5976
timeout=1,
5977
target_sysid=target_sysid,
5978
target_compid=target_compid,
5979
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
5980
)
5981
5982
def FlashStorage(self):
5983
'''Test flash storage (for parameters etc)'''
5984
self.set_parameter("LOG_BITMASK", 1)
5985
self.reboot_sitl()
5986
5987
self.customise_SITL_commandline([
5988
"--set-storage-posix-enabled", "0",
5989
"--set-storage-flash-enabled", "1",
5990
])
5991
if self.get_parameter("LOG_BITMASK") == 1:
5992
raise NotAchievedException("not using flash storage?")
5993
self.set_parameter("LOG_BITMASK", 2)
5994
self.reboot_sitl()
5995
self.assert_parameter_value("LOG_BITMASK", 2)
5996
self.set_parameter("LOG_BITMASK", 3)
5997
self.reboot_sitl()
5998
self.assert_parameter_value("LOG_BITMASK", 3)
5999
6000
self.customise_SITL_commandline([])
6001
# make sure we're back at our original value:
6002
self.assert_parameter_value("LOG_BITMASK", 1)
6003
6004
def FRAMStorage(self):
6005
'''Test FRAM storage (for parameters etc)'''
6006
self.set_parameter("LOG_BITMASK", 1)
6007
self.reboot_sitl()
6008
6009
self.customise_SITL_commandline([
6010
"--set-storage-posix-enabled", "0",
6011
"--set-storage-fram-enabled", "1",
6012
])
6013
# TODO: ensure w'ere actually taking stuff from flash storage:
6014
# if self.get_parameter("LOG_BITMASK") == 1:
6015
# raise NotAchievedException("not using flash storage?")
6016
self.set_parameter("LOG_BITMASK", 2)
6017
self.reboot_sitl()
6018
self.assert_parameter_value("LOG_BITMASK", 2)
6019
self.set_parameter("LOG_BITMASK", 3)
6020
self.reboot_sitl()
6021
self.assert_parameter_value("LOG_BITMASK", 3)
6022
6023
self.customise_SITL_commandline([])
6024
# make sure we're back at our original value:
6025
self.assert_parameter_value("LOG_BITMASK", 1)
6026
6027
def RangeFinder(self):
6028
'''Test RangeFinder'''
6029
# the following magic numbers correspond to the post locations in SITL
6030
home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 231)
6031
6032
rangefinder_params = {
6033
"SIM_SONAR_ROT": 0,
6034
}
6035
rangefinder_params.update(self.analog_rangefinder_parameters())
6036
6037
self.set_parameters(rangefinder_params)
6038
self.customise_SITL_commandline([
6039
"--home", home_string,
6040
])
6041
self.wait_ready_to_arm()
6042
if self.mavproxy is not None:
6043
self.mavproxy.send('script /tmp/post-locations.scr\n')
6044
m = self.assert_receive_message('RANGEFINDER', very_verbose=True)
6045
if m.voltage == 0:
6046
raise NotAchievedException("Did not get non-zero voltage")
6047
want_range = 10
6048
if abs(m.distance - want_range) > 0.5:
6049
raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance))
6050
6051
def DepthFinder(self):
6052
'''Test mulitple depthfinders for boats'''
6053
# Setup rangefinders
6054
self.customise_SITL_commandline([
6055
"--serial7=sim:nmea", # NMEA Rangefinder
6056
])
6057
6058
# RANGEFINDER_INSTANCES = [0, 2, 5]
6059
self.set_parameters({
6060
"RNGFND1_TYPE" : 17, # NMEA must attach uart to SITL
6061
"RNGFND1_ORIENT" : 25, # Set to downward facing
6062
"SERIAL7_PROTOCOL" : 9, # Rangefinder on serial7
6063
"SERIAL7_BAUD" : 9600, # Rangefinder specific baudrate
6064
6065
"RNGFND3_TYPE" : 2, # MaxbotixI2C
6066
"RNGFND3_ADDR" : 112, # 0x70 address from SIM_I2C.cpp
6067
"RNGFND3_ORIENT" : 0, # Set to forward facing, thus we should not receive DPTH messages from this one
6068
6069
"RNGFND6_ADDR" : 113, # 0x71 address from SIM_I2C.cpp
6070
"RNGFND6_ORIENT" : 25, # Set to downward facing
6071
"RNGFND6_TYPE" : 2, # MaxbotixI2C
6072
})
6073
6074
self.reboot_sitl()
6075
self.wait_ready_to_arm()
6076
6077
# should not get WATER_DEPTH messages or DPTH logs when the FRAME_CLASS is not a boat
6078
m = self.mav.recv_match(type="WATER_DEPTH", blocking=True, timeout=2)
6079
if m is not None:
6080
raise NotAchievedException("WATER_DEPTH: received message when FRAME_CLASS not a Boat")
6081
6082
# Set FRAME_CLASS to start receiving WATER_DEPTH messages & logging DPTH
6083
self.set_parameters({
6084
"FRAME_CLASS": 2, # Boat
6085
})
6086
6087
# Check each rangefinder instance is in collection
6088
rangefinder = [None, None, None, None, None, None] # Be lazy FIXME only need [3]
6089
6090
def check_rangefinder(mav, m):
6091
if m.get_type() != 'WATER_DEPTH':
6092
return
6093
6094
id = m.id
6095
6096
# Should not find instance 3 as it is forward facing
6097
if id == 2:
6098
raise NotAchievedException("Depthfinder Instance %i with non-downward orientation found" % (id))
6099
6100
rangefinder[id] = True
6101
6102
if id == 0:
6103
if float(m.temperature) == 0.0:
6104
raise NotAchievedException("Depthfinder Instance %i NMEA with temperature not found" % (id))
6105
elif id == 5:
6106
if float(m.temperature) != 0.0:
6107
raise NotAchievedException("Depthfinder Instance %i should not have temperature" % (id))
6108
6109
self.wait_ready_to_arm()
6110
self.arm_vehicle()
6111
6112
self.install_message_hook_context(check_rangefinder)
6113
self.drive_mission("rover1.txt", strict=False)
6114
6115
if rangefinder[0] is None:
6116
raise NotAchievedException("Never saw Depthfinder 1")
6117
if rangefinder[2] is not None:
6118
raise NotAchievedException("Should not have found a Depthfinder 3")
6119
if rangefinder[5] is None:
6120
raise NotAchievedException("Never saw Depthfinder 6")
6121
if not self.current_onboard_log_contains_message("DPTH"):
6122
raise NotAchievedException("Expected DPTH log message")
6123
6124
self.progress("Ensuring we get WATER_DEPTH at 12Hz with 2 backends")
6125
self.set_message_rate_hz('WATER_DEPTH', 12)
6126
self.assert_message_rate_hz('WATER_DEPTH', 12)
6127
6128
def EStopAtBoot(self):
6129
'''Ensure EStop prevents arming when asserted at boot time'''
6130
self.context_push()
6131
self.set_parameters({
6132
"RC9_OPTION": 31,
6133
})
6134
self.set_rc(9, 2000)
6135
self.reboot_sitl()
6136
self.assert_prearm_failure(
6137
"Motors Emergency Stopped",
6138
other_prearm_failures_fatal=False)
6139
self.context_pop()
6140
self.reboot_sitl()
6141
6142
def assert_mode(self, mode):
6143
if not self.mode_is(mode):
6144
raise NotAchievedException("Mode is not %s" % str(mode))
6145
6146
def ChangeModeByNumber(self):
6147
'''ensure we can set a mode by number, handy when we don't have a
6148
pymavlink number for it yet'''
6149
for (x, want) in (0, 'MANUAL'), (1, 'ACRO'), (3, 3):
6150
self.change_mode(x)
6151
self.assert_mode(want)
6152
6153
def StickMixingAuto(self):
6154
'''Ensure Stick Mixing works in auto'''
6155
items = []
6156
self.set_parameter('STICK_MIXING', 1)
6157
# home
6158
items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0),)
6159
# 1 waypoint a long way away
6160
items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),)
6161
self.upload_simple_relhome_mission(items)
6162
if self.mavproxy is not None:
6163
# handy for getting pretty pictures
6164
self.mavproxy.send("wp list\n")
6165
self.change_mode('AUTO')
6166
self.wait_ready_to_arm()
6167
self.arm_vehicle()
6168
self.set_rc(1, 1150)
6169
self.wait_heading(45)
6170
self.wait_heading(90)
6171
self.disarm_vehicle()
6172
6173
def AutoDock(self):
6174
'''Test automatic docking of rover for multiple FOVs of simulated beacon'''
6175
self.set_parameters({
6176
"PLND_ENABLED": 1,
6177
"PLND_TYPE": 4,
6178
"PLND_ORIENT": 0,
6179
})
6180
6181
start = self.mav.location()
6182
target = self.offset_location_ne(start, 50, 0)
6183
self.progress("Setting target to %f %f" % (start.lat, start.lng))
6184
stopping_dist = 0.5
6185
6186
self.set_parameters({
6187
"SIM_PLD_ENABLE": 1,
6188
"SIM_PLD_LAT": target.lat,
6189
"SIM_PLD_LON": target.lng,
6190
"SIM_PLD_HEIGHT": 0,
6191
"SIM_PLD_ALT_LMT": 30,
6192
"SIM_PLD_DIST_LMT": 30,
6193
"SIM_PLD_ORIENT": 4, # emit beams towards south, vehicle's heading must be north to see it
6194
"SIM_PLD_OPTIONS": 1,
6195
"DOCK_SPEED": 2,
6196
"DOCK_STOP_DIST": stopping_dist,
6197
})
6198
6199
for type in range(0, 3): # CYLINDRICAL FOV, CONICAL FOV, SPHERICAL FOV
6200
self.set_parameter("SIM_PLD_TYPE", type)
6201
self.reboot_sitl()
6202
self.change_mode('GUIDED')
6203
self.wait_ready_to_arm()
6204
self.arm_vehicle()
6205
initial_position = self.offset_location_ne(target, -20, -2)
6206
self.drive_to_location(initial_position)
6207
self.change_mode(8) # DOCK mode
6208
max_delta = 1
6209
self.wait_distance_to_location(target, 0, max_delta, timeout=180)
6210
self.disarm_vehicle()
6211
self.assert_receive_message('GLOBAL_POSITION_INT')
6212
new_pos = self.mav.location()
6213
delta = abs(self.get_distance(target, new_pos) - stopping_dist)
6214
self.progress("Docked %f metres from stopping point" % delta)
6215
if delta > max_delta:
6216
raise NotAchievedException("Did not dock close enough to stopping point (%fm > %fm" % (delta, max_delta))
6217
6218
if not self.current_onboard_log_contains_message("PL"):
6219
raise NotAchievedException("Did not see expected PL message")
6220
6221
self.progress("All done")
6222
6223
def PrivateChannel(self):
6224
'''test the serial option bit specifying a mavlink channel as private'''
6225
global mav2
6226
port = self.adjust_ardupilot_port(5763)
6227
mav2 = mavutil.mavlink_connection("tcp:localhost:%u" % port,
6228
robust_parsing=True,
6229
source_system=7,
6230
source_component=7)
6231
# send a heartbeat or two to make sure ArduPilot's aware:
6232
6233
def heartbeat_on_mav2(mav, m):
6234
'''send a heartbeat on mav2 whenever we get one on mav'''
6235
global mav2
6236
if mav == mav2:
6237
return
6238
if m.get_type() == 'HEARTBEAT':
6239
mav2.mav.heartbeat_send(
6240
mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
6241
mavutil.mavlink.MAV_AUTOPILOT_INVALID,
6242
0,
6243
0,
6244
0)
6245
return
6246
6247
self.assert_receive_message("HEARTBEAT", mav=mav2)
6248
6249
# ensure a targetted message is received:
6250
self.install_message_hook_context(heartbeat_on_mav2)
6251
6252
self.progress("Ensuring we can get a message normally")
6253
self.poll_message("AUTOPILOT_VERSION", mav=mav2)
6254
6255
self.progress("Polling AUTOPILOT_VERSION from random sysid")
6256
self.send_poll_message("AUTOPILOT_VERSION", mav=mav2, target_sysid=134)
6257
self.assert_not_receive_message("AUTOPILOT_VERSION", mav=mav2, timeout=10)
6258
6259
# make sure we get heartbeats on the main channel from the non-private mav2:
6260
tstart = self.get_sim_time()
6261
while True:
6262
if self.get_sim_time_cached() - tstart > 5:
6263
raise NotAchievedException("Did not get expected heartbeat from %u" % 7)
6264
m = self.assert_receive_message("HEARTBEAT")
6265
if m.get_srcSystem() == 7:
6266
self.progress("Got heartbeat from (%u) on non-private channel" % 7)
6267
break
6268
6269
# make sure we receive heartbeats from the autotest suite into
6270
# the component:
6271
tstart = self.get_sim_time()
6272
while True:
6273
if self.get_sim_time_cached() - tstart > 5:
6274
raise NotAchievedException("Did not get expected heartbeat from %u" % self.mav.source_system)
6275
m = self.assert_receive_message("HEARTBEAT", mav=mav2)
6276
if m.get_srcSystem() == self.mav.source_system:
6277
self.progress("Got heartbeat from (%u) on non-private channel" % self.mav.source_system)
6278
break
6279
6280
def printmessage(mav, m):
6281
global mav2
6282
if mav == mav2:
6283
return
6284
6285
print("Got (%u/%u) (%s) " % (m.get_srcSystem(), m.get_srcComponent(), str(m)))
6286
6287
# self.install_message_hook_context(printmessage)
6288
6289
# ensure setting the private channel mask doesn't cause us to
6290
# execute these commands:
6291
self.set_parameter("SERIAL2_OPTIONS", 1024)
6292
self.reboot_sitl() # mavlink-private is reboot-required
6293
mav2 = mavutil.mavlink_connection("tcp:localhost:5763",
6294
robust_parsing=True,
6295
source_system=7,
6296
source_component=7)
6297
# self.send_debug_trap()
6298
self.send_poll_message("AUTOPILOT_VERSION", mav=mav2, target_sysid=134)
6299
self.assert_not_receive_message("AUTOPILOT_VERSION", mav=mav2, timeout=10)
6300
6301
# make sure messages from a private channel don't make it to
6302
# the main channel:
6303
self.drain_mav(self.mav)
6304
self.drain_mav(mav2)
6305
6306
# make sure we do NOT get heartbeats on the main channel from
6307
# the private mav2:
6308
tstart = self.get_sim_time()
6309
while True:
6310
if self.get_sim_time_cached() - tstart > 5:
6311
break
6312
m = self.assert_receive_message("HEARTBEAT")
6313
if m.get_srcSystem() == 7:
6314
raise NotAchievedException("Got heartbeat from private channel")
6315
6316
self.progress("ensure no outside heartbeats reach private channels")
6317
tstart = self.get_sim_time()
6318
while True:
6319
if self.get_sim_time_cached() - tstart > 5:
6320
break
6321
m = self.assert_receive_message("HEARTBEAT")
6322
if m.get_srcSystem() == 1 and m.get_srcComponent() == 1:
6323
continue
6324
# note the above test which shows we get heartbeats from
6325
# both the vehicle and this tests's special heartbeat
6326
raise NotAchievedException("Got heartbeat on private channel from non-vehicle")
6327
6328
def MAV_CMD_DO_SET_REVERSE(self):
6329
'''test MAV_CMD_DO_SET_REVERSE command'''
6330
self.change_mode('GUIDED')
6331
self.wait_ready_to_arm()
6332
self.arm_vehicle()
6333
6334
here = self.mav.location()
6335
target_loc = self.offset_location_ne(here, 2000, 0)
6336
self.send_guided_mission_item(target_loc)
6337
6338
self.wait_groundspeed(3, 100, minimum_duration=5)
6339
6340
for method in self.run_cmd, self.run_cmd_int:
6341
self.progress("Forwards!")
6342
method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0)
6343
self.wait_heading(0)
6344
6345
self.progress("Backwards!")
6346
method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=1)
6347
self.wait_heading(180)
6348
6349
self.progress("Forwards!")
6350
method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0)
6351
self.wait_heading(0)
6352
6353
self.disarm_vehicle()
6354
6355
def MAV_CMD_NAV_RETURN_TO_LAUNCH(self):
6356
'''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command'''
6357
self.change_mode('GUIDED')
6358
self.wait_ready_to_arm()
6359
self.arm_vehicle()
6360
6361
here = self.mav.location()
6362
target_loc = self.offset_location_ne(here, 2000, 0)
6363
self.send_guided_mission_item(target_loc)
6364
self.wait_distance_to_home(20, 100)
6365
6366
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)
6367
self.wait_mode('RTL')
6368
6369
self.change_mode('GUIDED')
6370
6371
self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH)
6372
self.wait_mode('RTL')
6373
6374
self.wait_distance_to_home(0, 5, timeout=30)
6375
self.disarm_vehicle()
6376
6377
def MAV_CMD_DO_CHANGE_SPEED(self):
6378
'''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command'''
6379
self.change_mode('GUIDED')
6380
self.wait_ready_to_arm()
6381
self.arm_vehicle()
6382
6383
original_loc = self.mav.location()
6384
here = original_loc
6385
target_loc = self.offset_location_ne(here, 2000, 0)
6386
self.send_guided_mission_item(target_loc)
6387
self.wait_distance_to_home(20, 100)
6388
6389
speeds = 3, 7, 12, 4
6390
6391
for speed in speeds:
6392
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)
6393
self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5)
6394
6395
self.send_guided_mission_item(original_loc)
6396
6397
for speed in speeds:
6398
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed)
6399
self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5)
6400
6401
self.change_mode('RTL')
6402
6403
self.wait_distance_to_home(0, 5, timeout=30)
6404
self.disarm_vehicle()
6405
6406
def MAV_CMD_MISSION_START(self):
6407
'''simple test for starting missing using this command'''
6408
# home and 1 waypoint a long way away:
6409
self.upload_simple_relhome_mission([
6410
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0),
6411
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),
6412
])
6413
self.change_mode('AUTO')
6414
self.wait_ready_to_arm()
6415
self.arm_vehicle()
6416
for method in self.run_cmd, self.run_cmd_int:
6417
self.change_mode('MANUAL')
6418
self.wait_groundspeed(0, 1)
6419
method(mavutil.mavlink.MAV_CMD_MISSION_START)
6420
self.wait_mode('AUTO')
6421
self.wait_groundspeed(3, 100)
6422
self.disarm_vehicle()
6423
6424
def MAV_CMD_NAV_SET_YAW_SPEED(self):
6425
'''tests for MAV_CMD_NAV_SET_YAW_SPEED guided-mode command'''
6426
self.change_mode('GUIDED')
6427
self.wait_ready_to_arm()
6428
self.arm_vehicle()
6429
6430
for method in self.run_cmd, self.run_cmd_int:
6431
self.change_mode('MANUAL')
6432
self.wait_groundspeed(0, 1)
6433
self.change_mode('GUIDED')
6434
self.start_subtest("Absolute angles")
6435
for (heading, speed) in (10, 5), (190, 10), (0, 2), (135, 6):
6436
def cf(*args, **kwargs):
6437
method(
6438
mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,
6439
p1=heading,
6440
p2=speed,
6441
p3=0, # zero is absolute-angles
6442
)
6443
self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2)
6444
self.wait_heading(heading-0.5, heading+0.5, called_function=cf, minimum_duration=2)
6445
6446
self.start_subtest("relative angles")
6447
original_angle = 90
6448
method(
6449
mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,
6450
p1=original_angle,
6451
p2=5,
6452
p3=0, # zero is absolute-angles
6453
)
6454
self.wait_groundspeed(4, 6)
6455
self.wait_heading(original_angle-0.5, original_angle+0.5)
6456
6457
expected_angle = original_angle
6458
for (angle_delta, speed) in (5, 6), (-30, 2), (180, 7):
6459
method(
6460
mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,
6461
p1=angle_delta,
6462
p2=speed,
6463
p3=1, # one is relative-angles
6464
)
6465
6466
def cf(*args, **kwargs):
6467
method(
6468
mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED,
6469
p1=0,
6470
p2=speed,
6471
p3=1, # one is absolute-angles
6472
)
6473
expected_angle += angle_delta
6474
if expected_angle < 0:
6475
expected_angle += 360
6476
if expected_angle > 360:
6477
expected_angle -= 360
6478
self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2)
6479
self.wait_heading(expected_angle, called_function=cf, minimum_duration=2)
6480
self.do_RTL()
6481
self.disarm_vehicle()
6482
6483
def _MAV_CMD_GET_HOME_POSITION(self, run_cmd):
6484
'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''
6485
self.context_collect('HOME_POSITION')
6486
run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION)
6487
self.assert_receive_message('HOME_POSITION', check_context=True)
6488
6489
def MAV_CMD_GET_HOME_POSITION(self):
6490
'''test handling of mavlink command MAV_CMD_GET_HOME_POSITION'''
6491
self.change_mode('LOITER')
6492
self.wait_ready_to_arm()
6493
self._MAV_CMD_GET_HOME_POSITION(self.run_cmd)
6494
self._MAV_CMD_GET_HOME_POSITION(self.run_cmd_int)
6495
6496
def MAV_CMD_DO_FENCE_ENABLE(self):
6497
'''ensure MAV_CMD_DO_FENCE_ENABLE mavlink command works'''
6498
here = self.mav.location()
6499
6500
self.upload_fences_from_locations([
6501
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
6502
# east
6503
self.offset_location_ne(here, -50, 20), # bl
6504
self.offset_location_ne(here, 50, 20), # br
6505
self.offset_location_ne(here, 50, 40), # tr
6506
self.offset_location_ne(here, -50, 40), # tl,
6507
]),
6508
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [
6509
# over the top of the vehicle
6510
self.offset_location_ne(here, -50, -50), # bl
6511
self.offset_location_ne(here, -50, 50), # br
6512
self.offset_location_ne(here, 50, 50), # tr
6513
self.offset_location_ne(here, 50, -50), # tl,
6514
]),
6515
])
6516
6517
# enable:
6518
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1)
6519
self.assert_fence_enabled()
6520
6521
# disable
6522
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0)
6523
self.assert_fence_disabled()
6524
6525
def MAV_CMD_BATTERY_RESET(self):
6526
'''manipulate battery levels with MAV_CMD_BATTERY_RESET'''
6527
for (run_cmd, value) in (self.run_cmd, 56), (self.run_cmd_int, 97):
6528
run_cmd(
6529
mavutil.mavlink.MAV_CMD_BATTERY_RESET,
6530
p1=65535, # battery mask
6531
p2=value,
6532
)
6533
self.assert_received_message_field_values('BATTERY_STATUS', {
6534
"battery_remaining": value,
6535
}, {
6536
"poll": True,
6537
})
6538
6539
def TestWebServer(self, url):
6540
'''test active web server'''
6541
self.progress("Accessing webserver main page")
6542
import urllib.request
6543
6544
main_page = urllib.request.urlopen(url).read().decode('utf-8')
6545
if main_page.find('ArduPilot Web Server') == -1:
6546
raise NotAchievedException("Expected banner on main page")
6547
6548
board_status = urllib.request.urlopen(url + '/@DYNAMIC/board_status.shtml').read().decode('utf-8')
6549
if board_status.find('0 hours') == -1:
6550
raise NotAchievedException("Expected uptime in board status")
6551
if board_status.find('40.713') == -1:
6552
raise NotAchievedException("Expected lattitude in board status")
6553
6554
self.progress("WebServer tests OK")
6555
6556
def NetworkingWebServer(self):
6557
'''web server'''
6558
applet_script = "net_webserver.lua"
6559
6560
self.context_push()
6561
self.install_applet_script_context(applet_script)
6562
6563
self.set_parameters({
6564
"SCR_ENABLE": 1,
6565
"SCR_VM_I_COUNT": 1000000,
6566
"SIM_SPEEDUP": 20,
6567
"NET_ENABLE": 1,
6568
})
6569
6570
self.reboot_sitl()
6571
6572
self.context_push()
6573
self.context_collect('STATUSTEXT')
6574
6575
self.set_parameters({
6576
"WEB_BIND_PORT": 8081,
6577
})
6578
6579
self.scripting_restart()
6580
self.wait_text("WebServer: starting on port 8081", check_context=True)
6581
6582
self.wait_ready_to_arm()
6583
6584
self.TestWebServer("http://127.0.0.1:8081")
6585
6586
self.context_pop()
6587
self.context_pop()
6588
self.reboot_sitl()
6589
6590
def NetworkingWebServerPPP(self):
6591
'''web server over PPP'''
6592
applet_script = "net_webserver.lua"
6593
6594
self.context_push()
6595
self.install_applet_script_context(applet_script)
6596
6597
self.set_parameters({
6598
"SCR_ENABLE": 1,
6599
"SCR_VM_I_COUNT": 1000000,
6600
"SIM_SPEEDUP": 20,
6601
"NET_ENABLE": 1,
6602
"SERIAL5_PROTOCOL": 48,
6603
})
6604
6605
self.progress('rebuilding rover with ppp enabled')
6606
import shutil
6607
shutil.copy('build/sitl/bin/ardurover', 'build/sitl/bin/ardurover.noppp')
6608
util.build_SITL('bin/ardurover', clean=False, configure=True, extra_configure_args=['--enable-PPP', '--debug'])
6609
6610
self.reboot_sitl()
6611
6612
self.progress("Starting PPP daemon")
6613
pppd = util.start_PPP_daemon("192.168.14.15:192.168.14.13", '127.0.0.1:5765')
6614
6615
self.context_push()
6616
self.context_collect('STATUSTEXT')
6617
6618
pppd.expect("remote IP address 192.168.14.13")
6619
6620
self.progress("PPP daemon started")
6621
6622
self.set_parameters({
6623
"WEB_BIND_PORT": 8081,
6624
})
6625
6626
self.scripting_restart()
6627
self.wait_text("WebServer: starting on port 8081", check_context=True)
6628
6629
self.wait_ready_to_arm()
6630
6631
self.TestWebServer("http://192.168.14.13:8081")
6632
6633
self.context_pop()
6634
self.context_pop()
6635
6636
# restore rover without ppp enabled for next test
6637
os.unlink('build/sitl/bin/ardurover')
6638
shutil.copy('build/sitl/bin/ardurover.noppp', 'build/sitl/bin/ardurover')
6639
self.reboot_sitl()
6640
6641
def FenceFullAndPartialTransfer(self, target_system=1, target_component=1):
6642
'''ensure starting a fence transfer then a partial transfer behaves
6643
appropriately'''
6644
# start uploading a 10 item list:
6645
self.mav.mav.mission_count_send(
6646
target_system,
6647
target_component,
6648
10,
6649
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
6650
)
6651
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)
6652
# change our mind and try a partial mission upload:
6653
self.mav.mav.mission_write_partial_list_send(
6654
target_system,
6655
target_component,
6656
3,
6657
3,
6658
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
6659
# should get denied for that one:
6660
self.assert_receive_mission_ack(
6661
mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
6662
want_type=mavutil.mavlink.MAV_MISSION_DENIED,
6663
)
6664
# now wait for the original upload to be "cancelled"
6665
self.assert_receive_mission_ack(
6666
mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
6667
want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED,
6668
)
6669
6670
def MissionRetransfer(self, target_system=1, target_component=1):
6671
'''torture-test with MISSION_COUNT'''
6672
# self.send_debug_trap()
6673
self.mav.mav.mission_count_send(
6674
target_system,
6675
target_component,
6676
10,
6677
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
6678
)
6679
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)
6680
self.context_push()
6681
self.context_collect('STATUSTEXT')
6682
self.mav.mav.mission_count_send(
6683
target_system,
6684
target_component,
6685
10000,
6686
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
6687
)
6688
self.wait_statustext('Only [0-9]+ items are supported', regex=True, check_context=True)
6689
self.context_pop()
6690
self.assert_not_receive_message('MISSION_REQUEST')
6691
self.mav.mav.mission_count_send(
6692
target_system,
6693
target_component,
6694
10,
6695
mavutil.mavlink.MAV_MISSION_TYPE_FENCE
6696
)
6697
self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0)
6698
self.assert_receive_mission_ack(
6699
mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
6700
want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED,
6701
)
6702
6703
def MissionPolyEnabledPreArm(self):
6704
'''check Polygon porearm checks'''
6705
self.set_parameters({
6706
'FENCE_ENABLE': 1,
6707
})
6708
self.progress("Ensure that we can arm if polyfence is enabled but we have no polyfence")
6709
self.assert_parameter_value('FENCE_TYPE', 6)
6710
self.wait_ready_to_arm()
6711
self.reboot_sitl()
6712
self.wait_ready_to_arm()
6713
6714
self.progress("Ensure we can arm when we have an inclusion fence we are inside of")
6715
here = self.mav.location()
6716
self.upload_fences_from_locations([
6717
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
6718
# over the top of the vehicle
6719
self.offset_location_ne(here, -50, -50), # bl
6720
self.offset_location_ne(here, -50, 50), # br
6721
self.offset_location_ne(here, 50, 50), # tr
6722
self.offset_location_ne(here, 50, -50), # tl,
6723
]),
6724
])
6725
self.delay_sim_time(5)
6726
self.wait_ready_to_arm()
6727
6728
self.reboot_sitl()
6729
self.wait_ready_to_arm()
6730
6731
self.progress("Ensure we can't arm when we are in breacnh of a polyfence")
6732
self.clear_fence()
6733
6734
self.progress("Now create a fence we are in breach of")
6735
here = self.mav.location()
6736
self.upload_fences_from_locations([
6737
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
6738
# over the top of the vehicle
6739
self.offset_location_ne(here, 20, 20), # bl
6740
self.offset_location_ne(here, 20, 50), # br
6741
self.offset_location_ne(here, 50, 50), # tr
6742
self.offset_location_ne(here, 50, 20), # tl,
6743
]),
6744
])
6745
6746
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False)
6747
self.reboot_sitl()
6748
6749
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
6750
6751
self.progress("Ensure we can arm when a polyfence fence is cleared when we've previously been in breach")
6752
self.clear_fence()
6753
self.wait_ready_to_arm()
6754
6755
self.upload_fences_from_locations([
6756
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
6757
# over the top of the vehicle
6758
self.offset_location_ne(here, 20, 20), # bl
6759
self.offset_location_ne(here, 20, 50), # br
6760
self.offset_location_ne(here, 50, 50), # tr
6761
self.offset_location_ne(here, 50, 20), # tl,
6762
]),
6763
])
6764
self.reboot_sitl()
6765
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
6766
self.clear_fence()
6767
self.wait_ready_to_arm()
6768
6769
self.progress("Ensure we can arm after clearing polygon fence type enabled")
6770
self.upload_fences_from_locations([
6771
(mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
6772
# over the top of the vehicle
6773
self.offset_location_ne(here, 20, 20), # bl
6774
self.offset_location_ne(here, 20, 50), # br
6775
self.offset_location_ne(here, 50, 50), # tr
6776
self.offset_location_ne(here, 50, 20), # tl,
6777
]),
6778
])
6779
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
6780
self.set_parameter('FENCE_TYPE', 2)
6781
self.wait_ready_to_arm()
6782
self.set_parameter('FENCE_TYPE', 6)
6783
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
6784
6785
def OpticalFlow(self):
6786
'''lightly test OpticalFlow'''
6787
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, False, False, False, verbose=True)
6788
6789
self.context_push()
6790
self.set_parameter("SIM_FLOW_ENABLE", 1)
6791
self.set_parameter("FLOW_TYPE", 10)
6792
6793
self.reboot_sitl()
6794
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, True, True, True, verbose=True)
6795
6796
self.context_pop()
6797
self.reboot_sitl()
6798
6799
def RCDuplicateOptionsExist(self):
6800
'''ensure duplicate RC option detection works'''
6801
self.wait_ready_to_arm()
6802
self.set_parameters({
6803
"RC6_OPTION": 118,
6804
"RC7_OPTION": 118,
6805
})
6806
self.assert_arm_failure("Duplicate Aux Switch Options")
6807
6808
def JammingSimulation(self):
6809
'''Test jamming simulation works'''
6810
self.wait_ready_to_arm()
6811
start_loc = self.assert_receive_message('GPS_RAW_INT')
6812
self.set_parameter("SIM_GPS1_JAM", 1)
6813
6814
class Requirement():
6815
def __init__(self, field, min_value):
6816
self.field = field
6817
self.min_value = min_value
6818
6819
def met(self, m):
6820
return getattr(m, self.field) > self.min_value
6821
6822
requirements = set([
6823
Requirement('v_acc', 50000),
6824
Requirement('h_acc', 50000),
6825
Requirement('vel_acc', 1000),
6826
Requirement('vel', 10000),
6827
])
6828
low_sats_seen = False
6829
seen_bad_loc = False
6830
tstart = self.get_sim_time()
6831
6832
while True:
6833
if self.get_sim_time() - tstart > 120:
6834
raise NotAchievedException("Did not see all jamming")
6835
m = self.assert_receive_message('GPS_RAW_INT')
6836
new_requirements = copy.copy(requirements)
6837
for requirement in requirements:
6838
if requirement.met(m):
6839
new_requirements.remove(requirement)
6840
requirements = new_requirements
6841
if m.satellites_visible < 6:
6842
low_sats_seen = True
6843
here = self.assert_receive_message('GPS_RAW_INT')
6844
if self.get_distance_int(start_loc, here) > 100:
6845
seen_bad_loc = True
6846
6847
if len(requirements) == 0 and low_sats_seen and seen_bad_loc:
6848
break
6849
6850
def BatteryInvalid(self):
6851
'''check Battery prearms report useful data to user'''
6852
self.start_subtest("Changing battery types makes no difference")
6853
self.set_parameter("BATT_MONITOR", 0)
6854
self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)
6855
self.set_parameter("BATT_MONITOR", 4)
6856
self.wait_ready_to_arm()
6857
6858
self.start_subtest("No battery monitor should be armable")
6859
self.set_parameter("BATT_MONITOR", 0)
6860
self.reboot_sitl()
6861
self.wait_ready_to_arm()
6862
6863
self.set_parameter("BATT_MONITOR", 4)
6864
self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)
6865
self.reboot_sitl()
6866
self.wait_ready_to_arm()
6867
6868
self.start_subtest("Invalid backend should have a clear error")
6869
self.set_parameter("BATT_MONITOR", 98)
6870
self.reboot_sitl()
6871
self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)
6872
6873
self.start_subtest("Switching from an invalid backend to a valid backend should require a reboot")
6874
self.set_parameter("BATT_MONITOR", 4)
6875
self.assert_prearm_failure("Battery 1 unhealthy", other_prearm_failures_fatal=False)
6876
6877
self.start_subtest("Switching to None should NOT require a reboot")
6878
self.set_parameter("BATT_MONITOR", 0)
6879
self.wait_ready_to_arm()
6880
6881
# this method modified from cmd_addpoly in the MAVProxy code:
6882
def generate_polyfence(self, centre_loc, command, radius, count, rotation=0):
6883
'''adds a number of waypoints equally spaced around a circle
6884
6885
'''
6886
if count < 3:
6887
raise ValueError("Invalid count (%s)" % str(count))
6888
if radius <= 0:
6889
raise ValueError("Invalid radius (%s)" % str(radius))
6890
6891
latlon = (centre_loc.lat, centre_loc.lng)
6892
6893
items = []
6894
for i in range(0, count):
6895
(lat, lon) = mavextra.gps_newpos(latlon[0],
6896
latlon[1],
6897
360/float(count)*i + rotation,
6898
radius)
6899
6900
m = mavutil.mavlink.MAVLink_mission_item_int_message(
6901
1, # target system
6902
1, # target component
6903
0, # seq
6904
mavutil.mavlink.MAV_FRAME_GLOBAL, # frame
6905
command, # command
6906
0, # current
6907
0, # autocontinue
6908
count, # param1,
6909
0.0, # param2,
6910
0.0, # param3
6911
0.0, # param4
6912
int(lat*1e7), # x (latitude)
6913
int(lon*1e7), # y (longitude)
6914
0, # z (altitude)
6915
mavutil.mavlink.MAV_MISSION_TYPE_FENCE,
6916
)
6917
items.append(m)
6918
6919
return items
6920
6921
def SDPolyFence(self):
6922
'''test storage of fence on SD card'''
6923
self.set_parameters({
6924
'BRD_SD_FENCE': 32767,
6925
})
6926
self.reboot_sitl()
6927
6928
home = self.home_position_as_mav_location()
6929
fence = self.generate_polyfence(
6930
home,
6931
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION,
6932
radius=100,
6933
count=100,
6934
)
6935
6936
for bearing in range(0, 359, 60):
6937
x = self.offset_location_heading_distance(home, bearing, 100)
6938
fence.extend(self.generate_polyfence(
6939
x,
6940
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
6941
radius=100,
6942
count=100,
6943
))
6944
6945
self.correct_wp_seq_numbers(fence)
6946
self.check_fence_upload_download(fence)
6947
6948
self.delay_sim_time(1000)
6949
6950
def tests(self):
6951
'''return list of all tests'''
6952
ret = super(AutoTestRover, self).tests()
6953
6954
ret.extend([
6955
self.MAVProxy_SetModeUsingSwitch,
6956
self.HIGH_LATENCY2,
6957
self.MAVProxy_SetModeUsingMode,
6958
self.ModeSwitch,
6959
self.AuxModeSwitch,
6960
self.DriveRTL,
6961
self.SmartRTL,
6962
self.DriveSquare,
6963
self.DriveMission,
6964
# self.DriveBrake, # disabled due to frequent failures
6965
self.MAV_CMD_DO_SEND_BANNER,
6966
self.DO_SET_MODE,
6967
self.MAVProxy_DO_SET_MODE,
6968
self.ServoRelayEvents,
6969
self.RCOverrides,
6970
self.RCOverridesCancel,
6971
self.MANUAL_CONTROL,
6972
self.Sprayer,
6973
self.AC_Avoidance,
6974
self.CameraMission,
6975
self.Gripper,
6976
self.GripperMission,
6977
self.SET_MESSAGE_INTERVAL,
6978
self.MESSAGE_INTERVAL_COMMAND_INT,
6979
self.REQUEST_MESSAGE,
6980
self.SYSID_ENFORCE,
6981
self.SET_ATTITUDE_TARGET,
6982
self.SET_ATTITUDE_TARGET_heading,
6983
self.SET_POSITION_TARGET_LOCAL_NED,
6984
self.MAV_CMD_DO_SET_MISSION_CURRENT,
6985
self.MAV_CMD_DO_CHANGE_SPEED,
6986
self.MAV_CMD_MISSION_START,
6987
self.MAV_CMD_NAV_SET_YAW_SPEED,
6988
self.Button,
6989
self.Rally,
6990
self.Offboard,
6991
self.MAVProxyParam,
6992
self.GCSFence,
6993
self.GCSMission,
6994
self.GCSRally,
6995
self.MotorTest,
6996
self.WheelEncoders,
6997
self.DataFlashOverMAVLink,
6998
self.DataFlash,
6999
self.SkidSteer,
7000
self.PolyFence,
7001
self.SDPolyFence,
7002
self.PolyFenceAvoidance,
7003
self.PolyFenceObjectAvoidanceAuto,
7004
self.PolyFenceObjectAvoidanceGuided,
7005
self.PolyFenceObjectAvoidanceBendyRuler,
7006
self.SendToComponents,
7007
self.PolyFenceObjectAvoidanceBendyRulerEasierGuided,
7008
self.PolyFenceObjectAvoidanceBendyRulerEasierAuto,
7009
self.SlewRate,
7010
self.Scripting,
7011
self.ScriptingSteeringAndThrottle,
7012
self.MissionFrames,
7013
self.SetpointGlobalPos,
7014
self.SetpointGlobalVel,
7015
self.AccelCal,
7016
self.RangeFinder,
7017
self.AP_Proximity_MAV,
7018
self.EndMissionBehavior,
7019
self.FlashStorage,
7020
self.FRAMStorage,
7021
self.DepthFinder,
7022
self.ChangeModeByNumber,
7023
self.EStopAtBoot,
7024
self.MAV_CMD_NAV_RETURN_TO_LAUNCH,
7025
self.StickMixingAuto,
7026
self.AutoDock,
7027
self.PrivateChannel,
7028
self.GCSFailsafe,
7029
self.RoverInitialMode,
7030
self.DriveMaxRCIN,
7031
self.NoArmWithoutMissionItems,
7032
self.CompassPrearms,
7033
self.MAV_CMD_DO_SET_REVERSE,
7034
self.MAV_CMD_GET_HOME_POSITION,
7035
self.MAV_CMD_DO_FENCE_ENABLE,
7036
self.MAV_CMD_BATTERY_RESET,
7037
self.NetworkingWebServer,
7038
self.NetworkingWebServerPPP,
7039
self.RTL_SPEED,
7040
self.MissionRetransfer,
7041
self.FenceFullAndPartialTransfer,
7042
self.MissionPolyEnabledPreArm,
7043
self.OpticalFlow,
7044
self.RCDuplicateOptionsExist,
7045
self.ClearMission,
7046
self.JammingSimulation,
7047
self.BatteryInvalid,
7048
])
7049
return ret
7050
7051
def disabled_tests(self):
7052
return {
7053
"SlewRate": "got timing report failure on CI",
7054
"MAV_CMD_NAV_SET_YAW_SPEED": "compiled out of code by default",
7055
"PolyFenceObjectAvoidanceBendyRuler": "unreliable",
7056
}
7057
7058
def rc_defaults(self):
7059
ret = super(AutoTestRover, self).rc_defaults()
7060
ret[3] = 1500
7061
ret[8] = 1800
7062
return ret
7063
7064
def initial_mode_switch_mode(self):
7065
return "MANUAL"
7066
7067
def default_mode(self):
7068
return 'MANUAL'
7069
7070