mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28: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
e38adc7d14
commit
acd9fb9c0a
@ -6668,7 +6668,6 @@ class AutoTestCopter(AutoTest):
|
||||
raise ex
|
||||
|
||||
def wait_generator_speed_and_state(self, rpm_min, rpm_max, want_state, timeout=240):
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
@ -6812,7 +6811,6 @@ class AutoTestCopter(AutoTest):
|
||||
self.progress("Reset mission")
|
||||
self.set_rc(7, 2000)
|
||||
self.delay_sim_time(1)
|
||||
self.drain_mav()
|
||||
self.wait_current_waypoint(0, timeout=10)
|
||||
self.set_rc(7, 1000)
|
||||
|
||||
|
@ -802,7 +802,6 @@ class AutoTestPlane(AutoTest):
|
||||
# waypoint:
|
||||
self.wait_distance_to_waypoint(8, 100, 10000000)
|
||||
self.set_current_waypoint(8)
|
||||
self.drain_mav()
|
||||
# TODO: reflect on file to find this magic waypoint number?
|
||||
# self.wait_waypoint(7, num_wp-1, timeout=500) # we
|
||||
# tend to miss the final waypoint by a fair bit, and
|
||||
|
@ -5582,7 +5582,6 @@ class AutoTest(ABC):
|
||||
#################################################
|
||||
def delay_sim_time(self, seconds_to_wait, reason=None):
|
||||
"""Wait some second in SITL time."""
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time()
|
||||
tnow = tstart
|
||||
r = "Delaying %f seconds"
|
||||
@ -6691,7 +6690,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
def wait_ekf_flags(self, required_value, error_bits, timeout=30):
|
||||
self.progress("Waiting for EKF value %u" % required_value)
|
||||
self.drain_mav()
|
||||
last_print_time = 0
|
||||
tstart = self.get_sim_time()
|
||||
while timeout is None or self.get_sim_time_cached() < tstart + timeout:
|
||||
@ -7362,7 +7360,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
'''mavlink2 required'''
|
||||
target_system = 1
|
||||
target_component = 1
|
||||
self.drain_mav()
|
||||
self.progress("Sending mission_request_list")
|
||||
tstart = self.get_sim_time()
|
||||
self.mav.mav.mission_request_list_send(target_system,
|
||||
@ -7641,7 +7638,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
def zero_mag_offset_parameters(self, compass_count=3):
|
||||
self.progress("Zeroing Mag OFS parameters")
|
||||
self.drain_mav()
|
||||
self.get_sim_time()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS,
|
||||
2, # param1 (compass0)
|
||||
@ -7686,7 +7682,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
|
||||
def forty_two_mag_dia_odi_parameters(self, compass_count=3):
|
||||
self.progress("Forty twoing Mag DIA and ODI parameters")
|
||||
self.drain_mav()
|
||||
self.get_sim_time()
|
||||
params = [
|
||||
[("SIM_MAG_DIA_X", "COMPASS_DIA_X", 42.0),
|
||||
@ -7747,7 +7742,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
def reset_pos_and_start_magcal(mavproxy, tmask):
|
||||
mavproxy.send("sitl_stop\n")
|
||||
mavproxy.send("sitl_attitude 0 0 0\n")
|
||||
self.drain_mav()
|
||||
self.get_sim_time()
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
tmask, # p1: mag_mask
|
||||
@ -7804,7 +7798,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
if self.is_copter():
|
||||
# set frame class to pass arming check on copter
|
||||
self.set_parameter("FRAME_CLASS", 1)
|
||||
self.drain_mav()
|
||||
self.progress("Setting SITL Magnetometer model value")
|
||||
self.set_parameter("COMPASS_AUTO_ROT", 0)
|
||||
# MAG_ORIENT = 4
|
||||
@ -9058,7 +9051,6 @@ Also, ignores heartbeats not from our target system'''
|
||||
def poll_message(self, message_id, timeout=10):
|
||||
if type(message_id) == str:
|
||||
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
|
||||
self.drain_mav()
|
||||
tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work
|
||||
self.send_poll_message(message_id)
|
||||
self.run_cmd_get_ack(
|
||||
|
Loading…
Reference in New Issue
Block a user