Skip to content

Commit 7a6ac5a

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 3341f10 commit 7a6ac5a

File tree

1 file changed

+14
-7
lines changed

1 file changed

+14
-7
lines changed

libraries/SITL/SIM_Aircraft.cpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -32,10 +32,12 @@
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;
40+
extern const HAL_SITL& hal_sitl;
3941

4042
/*
4143
parent class for all simulator types
@@ -468,15 +470,20 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
468470
// @Field: VD: Velocity down
469471
// @Field: As: Airspeed
470472
// @Field: ASpdU: Achieved simulation speedup value
473+
// @Field: UFC: Number of times simulation paused for serial0 output
471474
Vector3d pos = get_position_relhome();
472475
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);
476+
AP::logger().WriteStreaming(
477+
"SIM2",
478+
"TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU,UFC",
479+
"QdddfffffI",
480+
AP_HAL::micros64(),
481+
pos.x, pos.y, pos.z,
482+
vel.x, vel.y, vel.z,
483+
airspeed_pitot,
484+
achieved_rate_hz/rate_hz,
485+
hal_sitl.get_uart_output_full_queue_count()
486+
);
480487
}
481488
#endif
482489
}

0 commit comments

Comments
 (0)