|
|
@ -29,15 +29,15 @@ namespace PX4 { |
|
|
|
#define KHZ (1000U) |
|
|
|
#define KHZ (1000U) |
|
|
|
|
|
|
|
|
|
|
|
SPIDesc SPIDeviceManager::device_table[] = { |
|
|
|
SPIDesc SPIDeviceManager::device_table[] = { |
|
|
|
SPIDesc("mpu6000", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 500*KHZ, 11*MHZ), |
|
|
|
SPIDesc("mpu6000", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 500*KHZ, 8*MHZ), |
|
|
|
#if defined(PX4_SPIDEV_EXT_BARO) |
|
|
|
#if defined(PX4_SPIDEV_EXT_BARO) |
|
|
|
SPIDesc("ms5611_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ), |
|
|
|
SPIDesc("ms5611_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ), |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
#if defined(PX4_SPIDEV_ICM) |
|
|
|
#if defined(PX4_SPIDEV_ICM) |
|
|
|
SPIDesc("icm20608", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ICM, SPIDEV_MODE3, 500*KHZ, 20*MHZ), |
|
|
|
SPIDesc("icm20608", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ICM, SPIDEV_MODE3, 500*KHZ, 8*MHZ), |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
// ICM20608 on the ACCEL_MAG
|
|
|
|
// ICM20608 on the ACCEL_MAG
|
|
|
|
SPIDesc("icm20608-am", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, SPIDEV_MODE3, 500*KHZ, 20*MHZ), |
|
|
|
SPIDesc("icm20608-am", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, SPIDEV_MODE3, 500*KHZ, 8*MHZ), |
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V4 |
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V4 |
|
|
|
SPIDesc("ms5611_int", PX4_SPI_BUS_BARO, (spi_dev_e)PX4_SPIDEV_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ), |
|
|
|
SPIDesc("ms5611_int", PX4_SPI_BUS_BARO, (spi_dev_e)PX4_SPIDEV_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ), |
|
|
|
#endif |
|
|
|
#endif |
|
|
@ -52,11 +52,11 @@ SPIDesc SPIDeviceManager::device_table[] = { |
|
|
|
#ifdef PX4_SPIDEV_EXT_GYRO |
|
|
|
#ifdef PX4_SPIDEV_EXT_GYRO |
|
|
|
SPIDesc("lsm9ds0_ext_g",PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ), |
|
|
|
SPIDesc("lsm9ds0_ext_g",PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ), |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
SPIDesc("mpu9250", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 20*MHZ), |
|
|
|
SPIDesc("mpu9250", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ), |
|
|
|
#ifdef PX4_SPIDEV_EXT_MPU |
|
|
|
#ifdef PX4_SPIDEV_EXT_MPU |
|
|
|
SPIDesc("mpu6000_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 500*KHZ, 11*MHZ),
|
|
|
|
SPIDesc("mpu6000_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 500*KHZ, 8*MHZ), |
|
|
|
SPIDesc("mpu9250_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 11*MHZ), |
|
|
|
SPIDesc("mpu9250_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ), |
|
|
|
SPIDesc("icm20608_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 11*MHZ), |
|
|
|
SPIDesc("icm20608_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ), |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
#ifdef PX4_SPIDEV_HMC |
|
|
|
#ifdef PX4_SPIDEV_HMC |
|
|
|
SPIDesc("hmc5843", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_HMC, SPIDEV_MODE3, 11*MHZ, 11*MHZ), |
|
|
|
SPIDesc("hmc5843", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_HMC, SPIDEV_MODE3, 11*MHZ, 11*MHZ), |
|
|
@ -236,7 +236,7 @@ SPIDeviceManager::get_device(const char *name) |
|
|
|
} |
|
|
|
} |
|
|
|
busp->next = buses; |
|
|
|
busp->next = buses; |
|
|
|
busp->bus = desc.bus; |
|
|
|
busp->bus = desc.bus; |
|
|
|
busp->dev = up_spiinitialize(desc.bus); |
|
|
|
busp->dev = up_spiinitialize(desc.bus); |
|
|
|
buses = busp; |
|
|
|
buses = busp; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|