HAL_ChibiOS: log SPI and I2C counters

This commit is contained in:
Andrew Tridgell 2019-05-16 17:57:35 +10:00
parent e64c5ef354
commit 59678840a8
3 changed files with 9 additions and 2 deletions

View File

@ -258,6 +258,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg);
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
osalSysLock();
hal.util->persistent_data.i2c_count++;
osalSysUnlock();
if(send_len == 0) {
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv, recv_len, chTimeMS2I(timeout_ms));
} else {

View File

@ -187,6 +187,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
#else
bus.bouncebuffer_setup(send, len, recv, len);
osalSysLock();
hal.util->persistent_data.spi_count++;
if (send == nullptr) {
spiStartReceiveI(spi_devices[device_desc.bus].driver, len, recv);
} else if (recv == nullptr) {

View File

@ -351,7 +351,7 @@ void Scheduler::_monitor_thread(void *arg)
// the main loop has been stuck for at least
// 200ms. Starting logging the main loop state
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QIbIIHHH",
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII",
AP_HAL::micros64(),
loop_delay,
pd.scheduler_task,
@ -359,7 +359,9 @@ void Scheduler::_monitor_thread(void *arg)
pd.internal_error_count,
pd.last_mavlink_msgid,
pd.last_mavlink_cmd,
pd.semaphore_line);
pd.semaphore_line,
pd.spi_count,
pd.i2c_count);
}
if (loop_delay >= 500) {
// at 500ms we declare an internal error