mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: make not having bus lock a soft error
this is nicer for driver developers
This commit is contained in:
parent
abd659212e
commit
9301e4888a
@ -160,7 +160,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("ERR: I2C transfer by non-owner\n");
|
||||
hal.console->printf("I2C: not owner of 0x%x\n", (unsigned)get_bus_id());
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -196,7 +196,10 @@ uint16_t SPIDevice::derive_freq_flag(uint32_t _frequency)
|
||||
bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
bus.semaphore.assert_owner();
|
||||
if (!bus.semaphore.check_owner()) {
|
||||
hal.console->printf("SPI: not owner of 0x%x\n", unsigned(get_bus_id()));
|
||||
return false;
|
||||
}
|
||||
if (send_len == recv_len && send == recv) {
|
||||
// simplest cases, needed for DMA
|
||||
do_transfer(send, recv, recv_len);
|
||||
|
Loading…
Reference in New Issue
Block a user