Skip to content

Commit 3748aa3

Browse files
committed
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.
1 parent ce52948 commit 3748aa3

File tree

1 file changed

+26
-7
lines changed

1 file changed

+26
-7
lines changed

libraries/SITL/SIM_Aircraft.cpp

Lines changed: 26 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -32,11 +32,17 @@
3232
#include <AP_JSON/AP_JSON.h>
3333
#include <AP_Filesystem/AP_Filesystem.h>
3434
#include <AP_AHRS/AP_AHRS.h>
35+
#include <AP_HAL_SITL/HAL_SITL_Class.h>
3536

3637
using namespace SITL;
3738

3839
extern const AP_HAL::HAL& hal;
3940

41+
// 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
42+
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
43+
extern const HAL_SITL& hal_sitl;
44+
#endif
45+
4046
/*
4147
parent class for all simulator types
4248
*/
@@ -452,6 +458,14 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
452458
}
453459

454460
#if HAL_LOGGING_ENABLED
461+
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
462+
// the SITL HAL can add information about pausing the simulation
463+
// and its effect on the UART. Not present when we're compiling
464+
// for simulation-on-hardware
465+
const uint32_t full_count = hal_sitl.get_uart_output_full_queue_count();
466+
#else
467+
const uint32_t full_count = 0;
468+
#endif
455469
// for EKF comparison log relhome pos and velocity at loop rate
456470
static uint16_t last_ticks;
457471
uint16_t ticks = AP::scheduler().ticks();
@@ -468,15 +482,20 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
468482
// @Field: VD: Velocity down
469483
// @Field: As: Airspeed
470484
// @Field: ASpdU: Achieved simulation speedup value
485+
// @Field: UFC: Number of times simulation paused for serial0 output
471486
Vector3d pos = get_position_relhome();
472487
Vector3f vel = get_velocity_ef();
473-
AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU",
474-
"Qdddfffff",
475-
AP_HAL::micros64(),
476-
pos.x, pos.y, pos.z,
477-
vel.x, vel.y, vel.z,
478-
airspeed_pitot,
479-
achieved_rate_hz/rate_hz);
488+
AP::logger().WriteStreaming(
489+
"SIM2",
490+
"TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU,UFC",
491+
"QdddfffffI",
492+
AP_HAL::micros64(),
493+
pos.x, pos.y, pos.z,
494+
vel.x, vel.y, vel.z,
495+
airspeed_pitot,
496+
achieved_rate_hz/rate_hz,
497+
full_count
498+
);
480499
}
481500
#endif
482501
}

0 commit comments

Comments
 (0)