Skip to content

Commit

Permalink
AP_HAL_SITL: process inbound data in outqueue-length delay loop
Browse files Browse the repository at this point in the history
this is the loop which ensures the amount of data sent to the mavlink client (usually Python) is limited - if we don't do this then we lose vast amounts of data when running at large speedups.

By attempting to process inbound data we may realise that the TCP connection has been dropped, and in that case we will start to listen for another connection.

This allows you to terminate the sim_vehicle.py MAVProxy and have it automagically restart (when running under GDB).  This is very useful for testing MAVProxy patches with SITL; it's a different workflow to opening an output and connecting a new version of MAVProxy to that outout.
  • Loading branch information
peterbarker authored and tridge committed Nov 12, 2024
1 parent 2ad8477 commit 3716f55
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AP_HAL_SITL/SITL_State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,12 +185,14 @@ void SITL_State::wait_clock(uint64_t wait_time_usec)
// conditions.
if (speedup > 1 && hal.scheduler->in_main_thread()) {
while (true) {
const int queue_length = ((HALSITL::UARTDriver*)hal.serial(0))->get_system_outqueue_length();
HALSITL::UARTDriver *uart = (HALSITL::UARTDriver*)hal.serial(0);
const int queue_length = uart->get_system_outqueue_length();
// ::fprintf(stderr, "queue_length=%d\n", (signed)queue_length);
if (queue_length < 1024) {
break;
}
_serial_0_outqueue_full_count++;
uart->handle_reading_from_device_to_readbuffer();
usleep(1000);
}
}
Expand Down

0 comments on commit 3716f55

Please sign in to comment.