SPIDevice::SPIDevice(SPIBus &bus, SPIDesc &device_desc) : _bus(bus) , _desc(device_desc) { set_device_bus(_bus.bus); set_device_address(_desc.subdev); if (_desc.cs_pin != SPI_CS_KERNEL) { _cs = hal.gpio->channel(_desc.cs_pin); if (!_cs) { AP_HAL::panic("Unable to instantiate cs pin"); } _cs->mode(HAL_GPIO_OUTPUT); // do not hold the SPI bus initially _cs_release(); } }
bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) { struct spi_ioc_transfer msgs[1] = { }; assert(_bus.fd >= 0); if (!send || !recv || len == 0) { return false; } msgs[0].tx_buf = (uint64_t) send; msgs[0].rx_buf = (uint64_t) recv; msgs[0].len = len; msgs[0].speed_hz = _speed; msgs[0].delay_usecs = 0; msgs[0].bits_per_word = _desc.bits_per_word; msgs[0].cs_change = 0; int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode); if (r < 0) { hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n", _bus.fd, strerror(errno)); return false; } _cs_assert(); r = ioctl(_bus.fd, SPI_IOC_MESSAGE(1), &msgs); _cs_release(); if (r == -1) { hal.console->printf("SPIDevice: error transferring data fd=%d (%s)\n", _bus.fd, strerror(errno)); return false; } return true; }
bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) { struct spi_ioc_transfer msgs[2] = { }; unsigned nmsgs = 0; assert(_bus.fd >= 0); if (send && send_len != 0) { msgs[nmsgs].tx_buf = (uint64_t) send; msgs[nmsgs].rx_buf = 0; msgs[nmsgs].len = send_len; msgs[nmsgs].speed_hz = _speed; msgs[nmsgs].delay_usecs = 0; msgs[nmsgs].bits_per_word = _desc.bits_per_word; msgs[nmsgs].cs_change = 0; nmsgs++; } if (recv && recv_len != 0) { msgs[nmsgs].tx_buf = 0; msgs[nmsgs].rx_buf = (uint64_t) recv; msgs[nmsgs].len = recv_len; msgs[nmsgs].speed_hz = _speed; msgs[nmsgs].delay_usecs = 0; msgs[nmsgs].bits_per_word = _desc.bits_per_word; msgs[nmsgs].cs_change = 0; nmsgs++; } if (!nmsgs) { return false; } int r; if (_bus.last_mode == _desc.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 we last used the bus. We want to report when this happens so the user has a chance of figuring out when there is conflicted use of the SPI bus. Unfortunately this costs us an extra syscall per transfer. */ uint8_t current_mode; if (ioctl(_bus.fd, SPI_IOC_RD_MODE, ¤t_mode) < 0) { hal.console->printf("SPIDevice: error on getting mode fd=%d (%s)\n", _bus.fd, strerror(errno)); _bus.last_mode = -1; } else if (current_mode != _bus.last_mode) { hal.console->printf("SPIDevice: bus mode conflict fd=%d mode=%u/%u\n", _bus.fd, (unsigned)_bus.last_mode, (unsigned)current_mode); _bus.last_mode = -1; } } if (_desc.mode != _bus.last_mode) { r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode); if (r < 0) { hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n", _bus.fd, strerror(errno)); return false; } _bus.last_mode = _desc.mode; } _cs_assert(); r = ioctl(_bus.fd, SPI_IOC_MESSAGE(nmsgs), &msgs); _cs_release(); if (r == -1) { hal.console->printf("SPIDevice: error transferring data fd=%d (%s)\n", _bus.fd, strerror(errno)); return false; } return true; }