mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: remove unused constant
This commit is contained in:
parent
5ba20b1763
commit
2296139516
@ -161,7 +161,7 @@ void SPIDeviceManager::init()
|
||||
}
|
||||
char path[255];
|
||||
snprintf(path, sizeof(path), "/dev/spidev%u.%u",
|
||||
_device[i]._bus + LINUX_SPIDEV_BUS_OFFSET, _device[i]._subdev);
|
||||
_device[i]._bus, _device[i]._subdev);
|
||||
_device[i]._fd = open(path, O_RDWR);
|
||||
if (_device[i]._fd == -1) {
|
||||
printf("Unable to open %s - %s\n", path, strerror(errno));
|
||||
|
@ -5,11 +5,6 @@
|
||||
#include "AP_HAL_Linux.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
// Most platforms won't need to declare the spidev bus offset
|
||||
#ifndef LINUX_SPIDEV_BUS_OFFSET
|
||||
#define LINUX_SPIDEV_BUS_OFFSET 0
|
||||
#endif
|
||||
|
||||
#define LINUX_SPI_MAX_BUSES 3
|
||||
|
||||
// Fake CS pin to indicate in-kernel handling
|
||||
|
Loading…
Reference in New Issue
Block a user