mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: SPI: adapt to the new signature of transaction()
This commit is contained in:
parent
e05928a7e8
commit
4af2a9a9cc
|
@ -90,9 +90,9 @@ AP_HAL::Semaphore* LinuxSPIDeviceDriver::get_semaphore()
|
|||
return LinuxSPIDeviceManager::get_semaphore(_bus);
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
bool LinuxSPIDeviceDriver::transaction(const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
LinuxSPIDeviceManager::transaction(*this, tx, rx, len);
|
||||
return LinuxSPIDeviceManager::transaction(*this, tx, rx, len);
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceDriver::set_bus_speed(enum bus_speed speed)
|
||||
|
@ -210,11 +210,16 @@ void LinuxSPIDeviceManager::cs_release(enum AP_HAL::SPIDevice type)
|
|||
}
|
||||
}
|
||||
|
||||
void LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
bool LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len)
|
||||
{
|
||||
int r;
|
||||
// we set the mode before we assert the CS line so that the bus is
|
||||
// in the correct idle state before the chip is selected
|
||||
ioctl(driver._fd, SPI_IOC_WR_MODE, &driver._mode);
|
||||
r = ioctl(driver._fd, SPI_IOC_WR_MODE, &driver._mode);
|
||||
if (r == -1) {
|
||||
hal.console->printf("SPI: error on setting mode\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
cs_assert(driver._type);
|
||||
struct spi_ioc_transfer spi[1];
|
||||
|
@ -232,8 +237,15 @@ void LinuxSPIDeviceManager::transaction(LinuxSPIDeviceDriver &driver, const uint
|
|||
memset(rx, 0, len);
|
||||
}
|
||||
|
||||
ioctl(driver._fd, SPI_IOC_MESSAGE(1), &spi);
|
||||
r = ioctl(driver._fd, SPI_IOC_MESSAGE(1), &spi);
|
||||
cs_release(driver._type);
|
||||
|
||||
if (r == -1) {
|
||||
hal.console->printf("SPI: error on doing transaction\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -21,7 +21,7 @@ public:
|
|||
LinuxSPIDeviceDriver(uint16_t bus, uint16_t subdev, enum AP_HAL::SPIDevice type, uint8_t mode, uint8_t bitsPerWord, int16_t cs_pin, uint32_t lowspeed, uint32_t highspeed);
|
||||
void init();
|
||||
AP_HAL::Semaphore *get_semaphore();
|
||||
void transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
void cs_assert();
|
||||
void cs_release();
|
||||
|
@ -55,7 +55,7 @@ public:
|
|||
|
||||
static void cs_assert(enum AP_HAL::SPIDevice type);
|
||||
static void cs_release(enum AP_HAL::SPIDevice type);
|
||||
static void transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
static bool transaction(LinuxSPIDeviceDriver &driver, const uint8_t *tx, uint8_t *rx, uint16_t len);
|
||||
|
||||
private:
|
||||
static LinuxSPIDeviceDriver _device[];
|
||||
|
|
Loading…
Reference in New Issue