mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ChibiOS: Console output can be disabled
This commit is contained in:
parent
a19d4b65fc
commit
e007b21f9e
@ -529,7 +529,7 @@ AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
|
|||||||
return _channels[j];
|
return _channels[j];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.console->printf("Out of analog channels\n");
|
DEV_PRINTF("Out of analog channels\n");
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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;
|
bus.i2ccfg.duty_cycle = STD_DUTY_CYCLE;
|
||||||
}
|
}
|
||||||
#endif
|
#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)
|
uint8_t *recv, uint32_t recv_len)
|
||||||
{
|
{
|
||||||
if (!bus.semaphore.check_owner()) {
|
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;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -451,16 +451,16 @@ SPIDeviceManager::get_device(const char *name)
|
|||||||
void SPIDevice::test_clock_freq(void)
|
void SPIDevice::test_clock_freq(void)
|
||||||
{
|
{
|
||||||
// delay for USB to come up
|
// 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++) {
|
for (uint8_t i=0; i<3; i++) {
|
||||||
hal.scheduler->delay(1000);
|
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; i<ARRAY_SIZE(bus_clocks); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(bus_clocks); i++) {
|
||||||
hal.console->printf("%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
|
// we will send 1024 bytes without any CS asserted and measure the
|
||||||
// time it takes to do the transfer
|
// time it takes to do the transfer
|
||||||
@ -485,7 +485,7 @@ void SPIDevice::test_clock_freq(void)
|
|||||||
chSysUnlock();
|
chSysUnlock();
|
||||||
if (msg == MSG_TIMEOUT) {
|
if (msg == MSG_TIMEOUT) {
|
||||||
spiAbort(spi_devices[i].driver);
|
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);
|
spiStop(spi_devices[i].driver);
|
||||||
spiReleaseBus(spi_devices[i].driver);
|
spiReleaseBus(spi_devices[i].driver);
|
||||||
continue;
|
continue;
|
||||||
@ -493,7 +493,7 @@ void SPIDevice::test_clock_freq(void)
|
|||||||
uint32_t t1 = AP_HAL::micros();
|
uint32_t t1 = AP_HAL::micros();
|
||||||
spiStop(spi_devices[i].driver);
|
spiStop(spi_devices[i].driver);
|
||||||
spiReleaseBus(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(buf1, len, AP_HAL::Util::MEM_DMA_SAFE);
|
||||||
hal.util->free_type(buf2, len, AP_HAL::Util::MEM_DMA_SAFE);
|
hal.util->free_type(buf2, len, AP_HAL::Util::MEM_DMA_SAFE);
|
||||||
|
@ -226,7 +226,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
|||||||
_timer_proc[_num_timer_procs] = proc;
|
_timer_proc[_num_timer_procs] = proc;
|
||||||
_num_timer_procs++;
|
_num_timer_procs++;
|
||||||
} else {
|
} else {
|
||||||
hal.console->printf("Out of timer processes\n");
|
DEV_PRINTF("Out of timer processes\n");
|
||||||
}
|
}
|
||||||
chBSemSignal(&_timer_semaphore);
|
chBSemSignal(&_timer_semaphore);
|
||||||
}
|
}
|
||||||
@ -245,7 +245,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
|||||||
_io_proc[_num_io_procs] = proc;
|
_io_proc[_num_io_procs] = proc;
|
||||||
_num_io_procs++;
|
_num_io_procs++;
|
||||||
} else {
|
} else {
|
||||||
hal.console->printf("Out of IO processes\n");
|
DEV_PRINTF("Out of IO processes\n");
|
||||||
}
|
}
|
||||||
chBSemSignal(&_io_semaphore);
|
chBSemSignal(&_io_semaphore);
|
||||||
}
|
}
|
||||||
|
@ -1156,7 +1156,7 @@ void UARTDriver::write_pending_bytes(void)
|
|||||||
}
|
}
|
||||||
if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) {
|
if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) {
|
||||||
// it doesn't look like hw flow control is working
|
// 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);
|
set_flow_control(FLOW_CONTROL_DISABLE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user