diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 99e76b1d1c..dd79b1997c 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -529,7 +529,7 @@ AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) return _channels[j]; } } - hal.console->printf("Out of analog channels\n"); + DEV_PRINTF("Out of analog channels\n"); return nullptr; } diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index 36e3ea9952..cc50bbacad 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -267,7 +267,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u bus.i2ccfg.duty_cycle = STD_DUTY_CYCLE; } #endif - hal.console->printf("I2C%u clock %ukHz\n", busnum, unsigned(bus.busclock/1000)); + DEV_PRINTF("I2C%u clock %ukHz\n", busnum, unsigned(bus.busclock/1000)); } } @@ -298,7 +298,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) { if (!bus.semaphore.check_owner()) { - hal.console->printf("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address); + DEV_PRINTF("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address); return false; } diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp index a6bf9e972f..73f7d99bf7 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.cpp @@ -451,16 +451,16 @@ SPIDeviceManager::get_device(const char *name) void SPIDevice::test_clock_freq(void) { // delay for USB to come up - hal.console->printf("Waiting for USB\n"); + DEV_PRINTF("Waiting for USB\n"); for (uint8_t i=0; i<3; i++) { hal.scheduler->delay(1000); - hal.console->printf("Waiting %u\n", (unsigned)AP_HAL::millis()); + DEV_PRINTF("Waiting %u\n", (unsigned)AP_HAL::millis()); } - hal.console->printf("CLOCKS=\n"); + DEV_PRINTF("CLOCKS=\n"); for (uint8_t i=0; iprintf("%u:%u ", unsigned(i+1), unsigned(bus_clocks[i])); + DEV_PRINTF("%u:%u ", unsigned(i+1), unsigned(bus_clocks[i])); } - hal.console->printf("\n"); + DEV_PRINTF("\n"); // we will send 1024 bytes without any CS asserted and measure the // time it takes to do the transfer @@ -485,7 +485,7 @@ void SPIDevice::test_clock_freq(void) chSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[i].driver); - hal.console->printf("SPI[%u] FAIL %p %p\n", spi_devices[i].busid, buf1, buf2); + DEV_PRINTF("SPI[%u] FAIL %p %p\n", spi_devices[i].busid, buf1, buf2); spiStop(spi_devices[i].driver); spiReleaseBus(spi_devices[i].driver); continue; @@ -493,7 +493,7 @@ void SPIDevice::test_clock_freq(void) uint32_t t1 = AP_HAL::micros(); spiStop(spi_devices[i].driver); spiReleaseBus(spi_devices[i].driver); - hal.console->printf("SPI[%u] clock=%u\n", unsigned(spi_devices[i].busid), unsigned(1000000ULL * len * 8ULL / uint64_t(t1 - t0))); + DEV_PRINTF("SPI[%u] clock=%u\n", unsigned(spi_devices[i].busid), unsigned(1000000ULL * len * 8ULL / uint64_t(t1 - t0))); } hal.util->free_type(buf1, len, AP_HAL::Util::MEM_DMA_SAFE); hal.util->free_type(buf2, len, AP_HAL::Util::MEM_DMA_SAFE); diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 66c8bb762b..b0beb3f477 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -226,7 +226,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc) _timer_proc[_num_timer_procs] = proc; _num_timer_procs++; } else { - hal.console->printf("Out of timer processes\n"); + DEV_PRINTF("Out of timer processes\n"); } chBSemSignal(&_timer_semaphore); } @@ -245,7 +245,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc) _io_proc[_num_io_procs] = proc; _num_io_procs++; } else { - hal.console->printf("Out of IO processes\n"); + DEV_PRINTF("Out of IO processes\n"); } chBSemSignal(&_io_semaphore); } diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index fe0b8f0e09..852841ec1f 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -1156,7 +1156,7 @@ void UARTDriver::write_pending_bytes(void) } if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) { // it doesn't look like hw flow control is working - hal.console->printf("disabling flow control on serial %u\n", sdef.get_index()); + DEV_PRINTF("disabling flow control on serial %u\n", sdef.get_index()); set_flow_control(FLOW_CONTROL_DISABLE); } }