mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: log number of times sim paused on serial0 buffer
SITL pauses the simulation if we do not have a minimum amount of space in its out queue. Log the number of times we do this.
This commit is contained in:
parent
7e59b8c5a0
commit
6ae0b5ec5b
|
@ -206,6 +206,11 @@ bool HAL_SITL::run_in_maintenance_mode() const
|
|||
}
|
||||
#endif
|
||||
|
||||
uint32_t HAL_SITL::get_uart_output_full_queue_count() const
|
||||
{
|
||||
return _sitl_state->_serial_0_outqueue_full_count;
|
||||
}
|
||||
|
||||
void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
|
||||
{
|
||||
assert(callbacks);
|
||||
|
|
|
@ -41,6 +41,8 @@ public:
|
|||
bool run_in_maintenance_mode() const;
|
||||
#endif
|
||||
|
||||
uint32_t get_uart_output_full_queue_count() const;
|
||||
|
||||
private:
|
||||
HALSITL::SITL_State *_sitl_state;
|
||||
|
||||
|
|
|
@ -188,6 +188,7 @@ void SITL_State::wait_clock(uint64_t wait_time_usec)
|
|||
if (queue_length < 1024) {
|
||||
break;
|
||||
}
|
||||
_serial_0_outqueue_full_count++;
|
||||
usleep(1000);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -247,6 +247,10 @@ public:
|
|||
void multicast_state_open(void);
|
||||
void multicast_state_send(void);
|
||||
|
||||
// number of times we have paused the simulation for 1ms because
|
||||
// the TCP queue is full:
|
||||
uint32_t _serial_0_outqueue_full_count;
|
||||
|
||||
protected:
|
||||
enum vehicle_type _vehicle;
|
||||
|
||||
|
|
Loading…
Reference in New Issue