mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
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.
This commit is contained in:
parent
2c6dd64c67
commit
ad8ab97725
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user