mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: pause/unpause SITL while draining mav
If Python can't keep up with the message volume coming from the autopilot we never manage to drain all messages from the vehicle. So try pausing/unpausing the simulation so we can drain the link... AT-1968.6: AP: PreArm: Radio failsafe on AT-1969.9: AP: PreArm: Radio failsafe on AT-1971.2: AP: PreArm: Radio failsafe on AT-1972.4: AP: PreArm: Radio failsafe on AT-1973.7: AP: PreArm: Radio failsafe on AT-1974.9: AP: PreArm: Radio failsafe on AT-1975.3: Drained 2000283 messages from mav (7218.974791/s) AT-1975.3: Exception caught: Traceback (most recent call last): File "/mnt/volume_nyc3_01/autotest/APM/APM/Tools/autotest/common.py", line 699 8, in run_one_test_attempt self.context_pop() File "/mnt/volume_nyc3_01/autotest/APM/APM/Tools/autotest/common.py", line 499 3, in context_pop self.set_parameters(dead_parameters_dict, add_to_context=False)
This commit is contained in:
parent
2eb3f75a57
commit
e38adc7d14
@ -14,6 +14,7 @@ import math
|
||||
import os
|
||||
import re
|
||||
import shutil
|
||||
import signal
|
||||
import sys
|
||||
import time
|
||||
import traceback
|
||||
@ -2558,6 +2559,16 @@ class AutoTest(ABC):
|
||||
self.apply_default_parameters()
|
||||
self.progress("Reset SITL commandline to default")
|
||||
|
||||
def pause_SITL(self):
|
||||
'''temporarily stop the SITL process from running. Note that
|
||||
simulation time will not move forward!'''
|
||||
# self.progress("Pausing SITL")
|
||||
self.sitl.kill(signal.SIGSTOP)
|
||||
|
||||
def unpause_SITL(self):
|
||||
# self.progress("Unpausing SITL")
|
||||
self.sitl.kill(signal.SIGCONT)
|
||||
|
||||
def stop_SITL(self):
|
||||
self.progress("Stopping SITL")
|
||||
self.expect_list_remove(self.sitl)
|
||||
@ -2737,6 +2748,7 @@ class AutoTest(ABC):
|
||||
tstart = time.time()
|
||||
timeout = 120
|
||||
failed_to_drain = False
|
||||
self.pause_SITL()
|
||||
while mav.recv_msg() is not None:
|
||||
count += 1
|
||||
if time.time() - tstart > timeout:
|
||||
@ -2745,6 +2757,7 @@ class AutoTest(ABC):
|
||||
# just die if that seems to be the case:
|
||||
failed_to_drain = True
|
||||
quiet = False
|
||||
self.unpause_SITL()
|
||||
if quiet:
|
||||
self.in_drain_mav = False
|
||||
return
|
||||
|
Loading…
Reference in New Issue
Block a user