Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: log number of times sim paused on serial0 buffer #27273

Merged
merged 2 commits into from
Jun 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions libraries/AP_HAL_SITL/HAL_SITL_Class.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL_SITL/HAL_SITL_Class.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ class HAL_SITL : public AP_HAL::HAL {
bool run_in_maintenance_mode() const;
#endif

uint32_t get_uart_output_full_queue_count() const;

private:
HALSITL::SITL_State *_sitl_state;

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL_SITL/SITL_State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL_SITL/SITL_State_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -247,6 +247,10 @@ class HALSITL::SITL_State_Common {
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;

Expand Down
33 changes: 26 additions & 7 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,17 @@
#include <AP_JSON/AP_JSON.h>
#include <AP_Filesystem/AP_Filesystem.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL_SITL/HAL_SITL_Class.h>

using namespace SITL;

extern const AP_HAL::HAL& hal;

// the SITL HAL can add information about pausing the simulation and its effect on the UART. Not present when we're compiling for simulation-on-hardware
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
extern const HAL_SITL& hal_sitl;
#endif

/*
parent class for all simulator types
*/
Expand Down Expand Up @@ -452,6 +458,14 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
}

#if HAL_LOGGING_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// the SITL HAL can add information about pausing the simulation
// and its effect on the UART. Not present when we're compiling
// for simulation-on-hardware
const uint32_t full_count = hal_sitl.get_uart_output_full_queue_count();
#else
const uint32_t full_count = 0;
#endif
// for EKF comparison log relhome pos and velocity at loop rate
static uint16_t last_ticks;
uint16_t ticks = AP::scheduler().ticks();
Expand All @@ -468,15 +482,20 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
// @Field: VD: Velocity down
// @Field: As: Airspeed
// @Field: ASpdU: Achieved simulation speedup value
// @Field: UFC: Number of times simulation paused for serial0 output
Vector3d pos = get_position_relhome();
Vector3f vel = get_velocity_ef();
AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU",
"Qdddfffff",
AP_HAL::micros64(),
pos.x, pos.y, pos.z,
vel.x, vel.y, vel.z,
airspeed_pitot,
achieved_rate_hz/rate_hz);
AP::logger().WriteStreaming(
"SIM2",
"TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU,UFC",
"QdddfffffI",
AP_HAL::micros64(),
pos.x, pos.y, pos.z,
vel.x, vel.y, vel.z,
airspeed_pitot,
achieved_rate_hz/rate_hz,
full_count
);
}
#endif
}
Expand Down
Loading