From ad8ab97725c1e7ca3541edb1d97a394866eb2a8a Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Thu, 9 Aug 2018 13:26:15 -0700 Subject: [PATCH] AP_HAL_Linux: SPIDevice: compile out debug stuff This should at most be behind a flag. If the device is being used by other process/drivers, it's a problem with that specific user/distro: don't penalize everybody else. Besides, changing the mode is not atomic and nothing guarantees the other side doesn't get scheduled and change it back before we get to run. --- libraries/AP_HAL_Linux/SPIDevice.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/SPIDevice.cpp b/libraries/AP_HAL_Linux/SPIDevice.cpp index baf4593eda..8c49f63dc5 100644 --- a/libraries/AP_HAL_Linux/SPIDevice.cpp +++ b/libraries/AP_HAL_Linux/SPIDevice.cpp @@ -37,6 +37,8 @@ #include "Thread.h" #include "Util.h" +#define DEBUG 0 + namespace Linux { static const AP_HAL::HAL &hal = AP_HAL::get_HAL(); @@ -295,8 +297,8 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len, return false; } - int r; - if (_bus.last_mode == _desc.mode) { +#if DEBUG + if (_desc.mode == _bus.last_mode) { /* the mode in the kernel is not tied to the file descriptor, so there is a chance some other process has changed it since @@ -316,6 +318,9 @@ bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len, _bus.last_mode = -1; } } +#endif + + int r; if (_desc.mode != _bus.last_mode) { r = ioctl(fd, SPI_IOC_WR_MODE, &_desc.mode); if (r < 0) {