mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: Ensure IOMCU does not log if there is no logger
This commit is contained in:
parent
e1e7c6ea8a
commit
52f2ec34fa
|
@ -328,14 +328,16 @@ void AP_IOMCU::read_status()
|
|||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_log_ms >= 1000U) {
|
||||
last_log_ms = now;
|
||||
AP::logger().Write("IOMC", "TimeUS,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHIIIII",
|
||||
AP_HAL::micros64(),
|
||||
reg_status.freemem,
|
||||
reg_status.timestamp_ms,
|
||||
reg_status.total_pkts,
|
||||
total_errors,
|
||||
reg_status.num_errors,
|
||||
num_delayed);
|
||||
if (AP_Logger::get_singleton()) {
|
||||
AP::logger().Write("IOMC", "TimeUS,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHIIIII",
|
||||
AP_HAL::micros64(),
|
||||
reg_status.freemem,
|
||||
reg_status.timestamp_ms,
|
||||
reg_status.total_pkts,
|
||||
total_errors,
|
||||
reg_status.num_errors,
|
||||
num_delayed);
|
||||
}
|
||||
#if IOMCU_DEBUG_ENABLE
|
||||
static uint32_t last_io_print;
|
||||
if (now - last_io_print >= 5000) {
|
||||
|
|
Loading…
Reference in New Issue