AP_HAL_Linux: added support for dynamic speed configration in LinuxSPIUARTDriver

This commit is contained in:
Staroselskii Georgii 2015-04-01 16:02:54 +03:00 committed by Andrew Tridgell
parent 47a336d192
commit 716fd56c62
2 changed files with 36 additions and 6 deletions

View File

@ -20,6 +20,7 @@ using namespace Linux;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define MHZ (1000U*1000U) #define MHZ (1000U*1000U)
#define KHZ (1000U)
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLE
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = { LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = {
@ -36,7 +37,7 @@ LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = { LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = {
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */ /* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
LinuxSPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 16*MHZ), LinuxSPIDeviceDriver(0, 1, AP_HAL::SPIDevice_MPU9250, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 16*MHZ),
LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 4*MHZ), LinuxSPIDeviceDriver(0, 0, AP_HAL::SPIDevice_Ublox, SPI_MODE_0, 8, SPI_CS_KERNEL, 250*KHZ, 4*MHZ),
}; };
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = { LinuxSPIDeviceDriver LinuxSPIDeviceManager::_device[LINUX_SPI_DEVICE_NUM_DEVICES] = {

View File

@ -9,10 +9,12 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define SPIUART_DEBUG 1 #define SPIUART_DEBUG 0
#if SPIUART_DEBUG
#include <cassert> #include <cassert>
#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#if SPIUART_DEBUG
#define debug(fmt, args ...) do {hal.console->printf("[SPIUARTDriver]: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) #define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
#else #else
#define debug(fmt, args ...) #define debug(fmt, args ...)
@ -86,7 +88,14 @@ void LinuxSPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_writebuf_tail = 0; _writebuf_tail = 0;
} }
_buffer = new uint8_t[rxS]; if (_buffer == NULL) {
/* Do not allocate new buffer, if we're just changing speed */
_buffer = new uint8_t[rxS];
if (_buffer == NULL) {
hal.console->printf("Not enough memory\n");
hal.scheduler->panic("Not enough memory\n");
}
}
_spi = hal.spi->device(AP_HAL::SPIDevice_Ublox); _spi = hal.spi->device(AP_HAL::SPIDevice_Ublox);
@ -96,7 +105,27 @@ void LinuxSPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_spi_sem = _spi->get_semaphore(); _spi_sem = _spi->get_semaphore();
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH); switch (b) {
case 4000000U:
if (is_initialized()) {
/* Do not allow speed changes before device is initialized, because
* it can lead to misconfiguraration. Once the device is initialized,
* it's sage to update speed
*/
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_HIGH);
debug("Set higher SPI-frequency");
} else {
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_LOW);
debug("Set lower SPI-frequency");
}
break;
default:
_spi->set_bus_speed(AP_HAL::SPIDeviceDriver::SPI_SPEED_LOW);
debug("Set lower SPI-frequency");
debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b);
break;
}
_initialised = true; _initialised = true;
} }