From b156fe5787b78007111e181438ba0991d3b132ea Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 20 Mar 2020 13:58:42 +0100 Subject: [PATCH] boards: remove deprecated SPI + I2C defines from board_config.h chip-selects are deselected in stm32_spiinitialize() --- boards/aerotenna/ocpoc/src/board_config.h | 17 -- boards/airmind/mindpx-v2/src/board_config.h | 75 ----- boards/airmind/mindpx-v2/src/init.c | 8 - boards/atlflight/eagle/src/board_config.h | 8 - boards/atlflight/excelsior/src/board_config.h | 8 - boards/av/x-v1/src/board_config.h | 95 ------- boards/av/x-v1/src/init.c | 4 +- boards/beaglebone/blue/src/board_config.h | 3 - boards/bitcraze/crazyflie/src/board_config.h | 39 +-- boards/emlid/navio2/src/board_config.h | 11 - boards/holybro/durandal-v1/src/board_config.h | 114 -------- boards/holybro/kakutef7/src/board_config.h | 40 --- boards/intel/aerofc-v1/src/board_config.h | 21 +- boards/modalai/fc-v1/init/rc.board_sensors | 2 +- boards/modalai/fc-v1/src/board_config.h | 127 --------- boards/mro/ctrl-zero-f7/src/board_config.h | 60 ---- boards/mro/x21-777/src/board_config.h | 44 --- boards/mro/x21/src/board_config.h | 44 --- boards/mro/x21/src/init.c | 3 - boards/nxp/fmuk66-v3/src/board_config.h | 60 ---- boards/nxp/fmurt1062-v1/default.cmake | 6 +- boards/nxp/fmurt1062-v1/src/board_config.h | 93 ------- .../nxp/rddrone-uavcan146/src/CMakeLists.txt | 1 + .../nxp/rddrone-uavcan146/src/board_config.h | 4 - boards/nxp/rddrone-uavcan146/src/i2c.cpp | 40 +++ boards/omnibus/f4sd/src/board_config.h | 81 ------ boards/omnibus/f4sd/src/init.c | 2 - boards/px4/fmu-v2/src/board_config.h | 263 +----------------- boards/px4/fmu-v2/src/spi.cpp | 110 ++++++++ boards/px4/fmu-v3/src/board_config.h | 263 +----------------- boards/px4/fmu-v3/src/spi.cpp | 110 ++++++++ boards/px4/fmu-v4/src/board_config.h | 97 ------- boards/px4/fmu-v4/src/init.c | 9 +- boards/px4/fmu-v4pro/src/board_config.h | 88 +----- boards/px4/fmu-v4pro/src/init.c | 8 - boards/px4/fmu-v5/src/board_config.h | 124 --------- boards/px4/fmu-v5x/src/board_config.h | 154 +--------- boards/px4/raspberrypi/src/board_config.h | 7 - boards/px4/sitl/src/board_config.h | 2 - boards/uvify/core/src/board_config.h | 99 ------- boards/uvify/core/src/init.c | 5 - 41 files changed, 278 insertions(+), 2071 deletions(-) create mode 100644 boards/nxp/rddrone-uavcan146/src/i2c.cpp diff --git a/boards/aerotenna/ocpoc/src/board_config.h b/boards/aerotenna/ocpoc/src/board_config.h index 6182198eef..0ec30309ea 100644 --- a/boards/aerotenna/ocpoc/src/board_config.h +++ b/boards/aerotenna/ocpoc/src/board_config.h @@ -49,27 +49,10 @@ #define BOARD_MAX_LEDS 1 // Number of external LED's this board has - -// I2C -#define PX4_I2C_BUS_EXPANSION 2 // i2c-2: Air Data Probe or I2C Splitter -#define PX4_I2C_BUS_EXPANSION1 4 // i2c-4: GPS/Compass #1 -#define PX4_I2C_BUS_EXPANSION2 5 // i2c-5: GPS/Compass #2 -#define PX4_I2C_BUS_EXPANSION3 3 // i2c-3: GPS/Compass #3 - #define PX4_NUMBER_I2C_BUSES 4 #define PX4_I2C_BUS_LED 1 -// SPI -#include -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) // spidev1.0 - mpu9250 -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) // spidev1.1 - ms5611 -//#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(0, 2) // TODO: where is the 2nd mpu9250? - -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - - // ADC channels: #define ADC_CHANNELS (1 << 8) diff --git a/boards/airmind/mindpx-v2/src/board_config.h b/boards/airmind/mindpx-v2/src/board_config.h index 68bd5bc0fd..0bb915f402 100644 --- a/boards/airmind/mindpx-v2/src/board_config.h +++ b/boards/airmind/mindpx-v2/src/board_config.h @@ -58,81 +58,6 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8) #define BOARD_OVERLOAD_LED LED_RED -/* External interrupts */ -#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN4) -#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) -#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) -#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN10) - -/* Data ready pins off */ -#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTE|GPIO_PIN14) -#define GPIO_MAG_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTC|GPIO_PIN14) -#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTC|GPIO_PIN13) -#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTE|GPIO_PIN10) - - -/* SPI1 off */ -#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5) -#define GPIO_SPI1_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN6) -#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN5) - -/*SPI1 chip selects off */ -#define GPIO_SPI_CS_FRAM_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTE|GPIO_PIN12) - -/* SPI1 chip selects */ -#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN12) - - -/* SPI4 off */ -#define GPIO_SPI4_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN2) -#define GPIO_SPI4_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN5) -#define GPIO_SPI4_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN6) - -/* SPI4 chip selects off */ -#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTB|GPIO_PIN2) -#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTD|GPIO_PIN11) -#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTE|GPIO_PIN3) - -/* SPI4 chip selects */ -#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN2) -#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11) -#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) - - -/* SPI2 off */ -#define GPIO_SPI2_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN13) -#define GPIO_SPI2_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI2_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15) - -/* SPI2 chip selects off */ -#define GPIO_SPI_CS_EXT0_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_25MHz|GPIO_PORTD|GPIO_PIN7) - -/* SPI2 chip selects */ -#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) - -#define PX4_SPI_BUS_SENSORS 4 -#define PX4_SPI_BUS_RAMTRON 1 -#define PX4_SPI_BUS_EXT 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI4 */ -#include -#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_L3GD20) -#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(0, DRV_ACC_DEVTYPE_LSM303D) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) - -/* External bus */ -#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(0, 0) - - -/* I2C busses */ -#define PX4_I2C_BUS_ONBOARD 1 -#define PX4_I2C_BUS_EXPANSION 2 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* * ADC channels * diff --git a/boards/airmind/mindpx-v2/src/init.c b/boards/airmind/mindpx-v2/src/init.c index f0680ad24e..acf6c1c713 100644 --- a/boards/airmind/mindpx-v2/src/init.c +++ b/boards/airmind/mindpx-v2/src/init.c @@ -259,10 +259,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi4, 10000000); SPI_SETBITS(spi4, 8); SPI_SETMODE(spi4, SPIDEV_MODE3); - SPI_SELECT(spi4, PX4_SPIDEV_GYRO, false); - SPI_SELECT(spi4, PX4_SPIDEV_ACCEL_MAG, false); - SPI_SELECT(spi4, PX4_SPIDEV_BARO, false); - SPI_SELECT(spi4, PX4_SPIDEV_MPU, false); up_udelay(20); /* Get the SPI port for the FRAM */ @@ -281,8 +277,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated SPI_SETFREQUENCY(spi1, 24 * 1000 * 1000); SPI_SETBITS(spi1, 8); - SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, SPIDEV_FLASH(0), false); spi2 = px4_spibus_initialize(2); @@ -290,8 +284,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) /* Default SPI2 to 10MHz and de-assert the known chip selects. */ SPI_SETFREQUENCY(spi2, 10000000); SPI_SETBITS(spi2, 8); - SPI_SETMODE(spi2, SPIDEV_MODE3); - SPI_SELECT(spi2, PX4_SPIDEV_EXT0, false); #ifdef CONFIG_MMCSD diff --git a/boards/atlflight/eagle/src/board_config.h b/boards/atlflight/eagle/src/board_config.h index 50869060f0..249cc1492a 100644 --- a/boards/atlflight/eagle/src/board_config.h +++ b/boards/atlflight/eagle/src/board_config.h @@ -48,16 +48,8 @@ /* * I2C busses */ -#define PX4_I2C_BUS_EXPANSION1 2 // I2C2: J9 / GPS -#define PX4_I2C_BUS_EXPANSION 3 // I2C3: J14 / Power -#define PX4_I2C_BUS_EXPANSION2 9 // I2C9: J15 / Radio Receiver / Sensors - #define PX4_NUMBER_I2C_BUSES 3 -// SPI -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) // spi-1 - mpu9250 - // Battery ADC channels #include diff --git a/boards/atlflight/excelsior/src/board_config.h b/boards/atlflight/excelsior/src/board_config.h index bebfbe1afd..449d655937 100644 --- a/boards/atlflight/excelsior/src/board_config.h +++ b/boards/atlflight/excelsior/src/board_config.h @@ -48,15 +48,7 @@ /* * I2C busses */ -#define PX4_I2C_BUS_EXPANSION1 2 // I2C2: J9 / GPS -#define PX4_I2C_BUS_EXPANSION 3 // I2C3: J14 / Power -#define PX4_I2C_BUS_EXPANSION2 9 // I2C9: J15 / Radio Receiver / Sensors - #define PX4_NUMBER_I2C_BUSES 3 -// SPI -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) - #include #include diff --git a/boards/av/x-v1/src/board_config.h b/boards/av/x-v1/src/board_config.h index ddaa996371..769656fe9c 100644 --- a/boards/av/x-v1/src/board_config.h +++ b/boards/av/x-v1/src/board_config.h @@ -54,101 +54,6 @@ #define BOARD_HAS_NBAT_V 1 // Only one Vbat to ADC #define BOARD_HAS_NBAT_I 0 // No Ibat ADC -#define PX4_SPI_BUS_SENSOR1 1 -#define PX4_SPI_BUS_EXTERNAL1 2 -#define PX4_SPI_BUS_SENSOR4 4 -#define PX4_SPI_BUS_SENSOR5 5 - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ -#define GPIO_SPI1_CS1_ADIS16477 /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) -#define GPIO_SPI1_RESET_ADIS16477 /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15) - -/* SPI 2 CS */ -#define GPIO_SPI2_CS1_ADIS16497 /* PI0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN0) - -/* SPI 4 CS */ -#define GPIO_SPI4_CS1_LPS22HB /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) - -/* SPI 5 CS */ -#define GPIO_SPI5_CS1_LSM303A_M /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) -#define GPIO_SPI5_CS1_LSM303A_X /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0) - -/* Define the SPI1 Data Ready interrupts */ -#define GPIO_SPI1_DRDY1_ADIS16477 /* PJ0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTJ|GPIO_PIN0) - -/* Define the SPI2 Data Ready interrupts */ -#define GPIO_SPI2_DRDY1_ADIS16497 /* PJ5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTJ|GPIO_PIN5) -#define SPI2_CS1_EXTERNAL1 GPIO_SPI2_DRDY1_ADIS16497 - -/* Define the SPI4 Data Ready interrupts */ -#define GPIO_SPI4_DRDY1_LPS22HB /* PK1 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTK|GPIO_PIN1) - -/* Define the SPI5 Data Ready interrupts */ -#define GPIO_SPI5_DRDY1_LSM303A_M /* PK7 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTK|GPIO_PIN7) -#define GPIO_SPI5_DRDY2_LSM303A_X /* PD12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN12) - -/* SPI1 off */ -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -/* SPI2 off */ -#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK) -#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO) -#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI) - -/* SPI4 off */ -#define GPIO_SPI4_SCK_OFF _PIN_OFF(GPIO_SPI4_SCK) -#define GPIO_SPI4_MISO_OFF _PIN_OFF(GPIO_SPI4_MISO) -#define GPIO_SPI4_MOSI_OFF _PIN_OFF(GPIO_SPI4_MOSI) - -/* SPI5 off */ -#define GPIO_SPI5_SCK_OFF _PIN_OFF(GPIO_SPI5_SCK) -#define GPIO_SPI5_MISO_OFF _PIN_OFF(GPIO_SPI5_MISO) -#define GPIO_SPI5_MOSI_OFF _PIN_OFF(GPIO_SPI5_MOSI) - - -#define GPIO_DRDY_OFF_SPI1_DRDY1_ADIS16477 _PIN_OFF(GPIO_SPI1_DRDY1_ADIS16477) -#define GPIO_DRDY_OFF_SPI2_DRDY1_ADIS16497 _PIN_OFF(GPIO_SPI2_DRDY1_ADIS16497) -#define GPIO_DRDY_OFF_SPI4_DRDY1_LPS22HB _PIN_OFF(GPIO_SPI4_DRDY1_LPS22HB) -#define GPIO_DRDY_OFF_SPI5_DRDY1_LSM303A_M _PIN_OFF(GPIO_SPI5_DRDY1_LSM303A_M) -#define GPIO_DRDY_OFF_SPI5_DRDY2_LSM303A_X _PIN_OFF(GPIO_SPI5_DRDY1_LSM303A_X) - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - - -#include -/* SPI1 */ -#define PX4_SPIDEV_ADIS16477 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ADIS16477) -#define PX4_SENSOR1_BUS_CS_GPIO {GPIO_SPI1_CS1_ADIS16477} - -/* SPI2 */ -#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(0,0) -#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI2_CS1_EXTERNAL1} - -/* SPI4 */ -#define PX4_SPIDEV_LPS22HB PX4_MK_SPI_SEL(0,DRV_BARO_DEVTYPE_LPS22HB) -#define PX4_SENSOR4_BUS_CS_GPIO {GPIO_SPI4_CS1_LPS22HB} - -/* SPI5 */ -#define PX4_SPIDEV_LSM303A_M PX4_MK_SPI_SEL(0,DRV_MAG_DEVTYPE_LSM303AGR) -#define PX4_SPIDEV_LSM303A_X PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_LSM303AGR) -#define PX4_SENSOR5_BUS_CS_GPIO {GPIO_SPI5_CS1_LSM303A_M, GPIO_SPI5_CS1_LSM303A_X} - -/* I2C busses */ -#define PX4_I2C_BUS_EXPANSION 2 -#define PX4_I2C_BUS_EXPANSION1 4 -#define PX4_I2C_BUS_ONBOARD 3 - -#define BOARD_NUMBER_I2C_BUSES 4 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} - /* * ADC channels * diff --git a/boards/av/x-v1/src/init.c b/boards/av/x-v1/src/init.c index f738902026..e6a99a75bd 100644 --- a/boards/av/x-v1/src/init.c +++ b/boards/av/x-v1/src/init.c @@ -206,8 +206,8 @@ static int configure_switch(void) { int ret = PX4_ERROR; - // attach to the i2c bus - struct i2c_master_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_ONBOARD); + // attach to the i2c bus (internal) + struct i2c_master_s *i2c = px4_i2cbus_initialize(3); if (i2c == NULL) { syslog(LOG_ERR, "[boot] I2C device not opened\n"); diff --git a/boards/beaglebone/blue/src/board_config.h b/boards/beaglebone/blue/src/board_config.h index e3361a1f80..a14f04dac5 100644 --- a/boards/beaglebone/blue/src/board_config.h +++ b/boards/beaglebone/blue/src/board_config.h @@ -50,9 +50,6 @@ // I2C -#define PX4_I2C_BUS_EXPANSION 1 // i2c-1: pins P9 17,18 -#define PX4_I2C_BUS_ONBOARD 2 // i2c-2: pins P9 19,20 - bmp280, mpu9250 - #define PX4_NUMBER_I2C_BUSES 2 #define PX4_I2C_OBDEV_MPU9250 0x68 diff --git a/boards/bitcraze/crazyflie/src/board_config.h b/boards/bitcraze/crazyflie/src/board_config.h index 6e29ea966e..eb534441dd 100644 --- a/boards/bitcraze/crazyflie/src/board_config.h +++ b/boards/bitcraze/crazyflie/src/board_config.h @@ -88,52 +88,15 @@ /* * I2C busses */ -#define PX4_I2C_BUS_ONBOARD 3 -#define PX4_I2C_BUS_EXPANSION 1 - #define PX4_I2C_BUS_ONBOARD_HZ 400000 #define PX4_I2C_BUS_EXPANSION_HZ 400000 -#define PX4_I2C_BUS_MTD PX4_I2C_BUS_EXPANSION +#define PX4_I2C_BUS_MTD 1 #define BOARD_NUMBER_I2C_BUSES 3 #define BOARD_I2C_BUS_CLOCK_INIT {PX4_I2C_BUS_ONBOARD_HZ, 100000, PX4_I2C_BUS_EXPANSION_HZ} -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - - -/* SPI Busses */ - -/* SPI1 Bus */ -#define PX4_SPI_BUS_EXPANSION 1 - -/* SPI1 CS */ -#define GPIO_SPI1_CS0_EXT /* PC12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN12) -#define GPIO_SPI1_CS1_EXT /* PB4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_CS2_EXT /* PB5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN5) - -#define PX4_FLOW_BUS_CS_GPIO { GPIO_SPI1_CS0_EXT, GPIO_SPI1_CS1_EXT, GPIO_SPI1_CS2_EXT } - -/* SPI1 Devices */ -#define PX4_SPIDEV_EXPANSION_1 SPIDEV_MMCSD(0) // SD CARD BREAKOUT -#define PX4_SPIDEV_EXPANSION_2 PX4_MK_SPI_SEL(0, DRV_FLOW_DEVTYPE_PMW3901) // OPTICAL FLOW BREAKOUT -#define PX4_SPIDEV_EXPANSION_3 PX4_MK_SPI_SEL(0, DRV_DEVTYPE_UNUSED) - -#define PX4_FLOW_BUS_FIRST_CS PX4_SPIDEV_EXPANSION_1 -#define PX4_FLOW_BUS_LAST_CS PX4_SPIDEV_EXPANSION_3 - -/* SPI1 off */ -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - - /* Devices on the onboard bus. * * Note that these are unshifted addresses. diff --git a/boards/emlid/navio2/src/board_config.h b/boards/emlid/navio2/src/board_config.h index dc0f0dbf91..21597fadd4 100644 --- a/boards/emlid/navio2/src/board_config.h +++ b/boards/emlid/navio2/src/board_config.h @@ -52,20 +52,9 @@ // I2C -#define PX4_I2C_BUS_EXPANSION 1 - #define PX4_NUMBER_I2C_BUSES 1 -// SPI -#include -#define PX4_SPI_BUS_SENSORS 0 -#define PX4_SPIDEV_UBLOX PX4_MK_SPI_SEL(0, 0) // spidev0.0 - ublox m8n -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) // spidev0.1 - mpu9250 -#define PX4_SPIDEV_LSM9DS1_M PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_ST_LSM9DS1_M) // spidev0.2 - lsm9ds1 mag -#define PX4_SPIDEV_LSM9DS1_AG PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ST_LSM9DS1_AG) // spidev0.3 - lsm9ds1 accel/gyro - - // ADC channels: // A0 - board voltage (shows 5V) // A1 - servo rail voltage diff --git a/boards/holybro/durandal-v1/src/board_config.h b/boards/holybro/durandal-v1/src/board_config.h index b9dd84bd14..7374874cc2 100644 --- a/boards/holybro/durandal-v1/src/board_config.h +++ b/boards/holybro/durandal-v1/src/board_config.h @@ -87,120 +87,6 @@ #define BOARD_OVERLOAD_LED LED_RED #define BOARD_ARMED_STATE_LED LED_BLUE -/* SENSORS are on SPI1, 5, 6 - * MEMORY is on bus SPI2 - * MS5611 is on bus SPI4 - */ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_SENSORS3 PX4_SPI_BUS_SENSORS // for BMI088 -#define PX4_SPI_BUS_MEMORY 2 -#define PX4_SPI_BUS_BARO 4 -#define PX4_SPI_BUS_EXTERNAL1 5 -#define PX4_SPI_BUS_EXTERNAL2 6 - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ - -#define GPIO_SPI1_CS1_ICM20689 /* PF2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN2) -#define GPIO_SPI1_CS3_BMI088_GYRO /* PF4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN4) -#define GPIO_SPI1_CS4_BMI088_ACC /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) -#define GPIO_SPI1_CS5_AUX_MEM /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) - - -/* Define the SPI1 Data Ready interrupts */ - -#define GPIO_SPI1_DRDY1_ICM20689 /* PB4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_DRDY2_BMI088_GYRO /* PB14 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI1_DRDY3_BMI088_ACC /* PB15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN15) -#define GPIO_SPI1_DRDY5_BMI088_GYRO /* PC13 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) -#define GPIO_SPI1_DRDY6_BMI088_ACC /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN10) - -/* SPI1 off */ - -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20689) -#define GPIO_DRDY_OFF_SPI1_DRDY2_BMI088_GYRO _PIN_OFF(GPIO_SPI1_DRDY2_BMI088_GYRO) -#define GPIO_DRDY_OFF_SPI1_DRDY3_BMI088_ACC _PIN_OFF(GPIO_SPI1_DRDY3_BMI088_ACC) -#define GPIO_DRDY_OFF_SPI1_DRDY5_BMI088_GYRO _PIN_OFF(GPIO_SPI1_DRDY5_BMI088_GYRO) -#define GPIO_DRDY_OFF_SPI1_DRDY6_BMI088_ACC _PIN_OFF(GPIO_SPI1_DRDY6_BMI088_ACC) - -/* SPI 2 CS */ - -#define GPIO_SPI2_CS_FRAM /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN5) - -/* SPI 4 CS */ - -#define GPIO_SPI4_CS1_MS5611 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) - -/* SPI 5 CS */ - -#define SPI5_CS1_EXTERNAL1 /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN4) -#define SPI5_CS2_EXTERNAL1 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) - -/* Define the SPI1 Data Ready and Control signals */ - -#define GPIO_SPI5_DRDY7_EXTERNAL1 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) - -/* SPI 6 */ - -#define SPI6_CS1_EXTERNAL2 /* PI6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6) -#define SPI6_CS2_EXTERNAL2 /* PI7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7) -#define SPI6_CS3_EXTERNAL2 /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN8) - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - - -#define GPIO_DRDY_OFF_SPI5_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI5_DRDY7_EXTERNAL1) - - -/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */ -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY -/* ^ END Legacy SPI defines TODO: fix this with enumeration */ - -#include -#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20689) -#define PX4_SPIDEV_BMI088_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI088) -#define PX4_SPIDEV_BMI088_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI088) -#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(0,DRV_DEVTYPE_UNUSED) -#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS3_BMI088_GYRO, GPIO_SPI1_CS4_BMI088_ACC, GPIO_SPI1_CS5_AUX_MEM} - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI2_CS_FRAM} - -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0,DRV_BARO_DEVTYPE_MS5611) -#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI4_CS1_MS5611} - -#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(0,0) -#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(0,1) -#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI5_CS1_EXTERNAL1, SPI5_CS2_EXTERNAL1} - -#define PX4_SPIDEV_EXTERNAL2_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,0) -#define PX4_SPIDEV_EXTERNAL2_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,1) -#define PX4_SPIDEV_EXTERNAL2_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,2) -#define PX4_EXTERNAL2_BUS_CS_GPIO {SPI6_CS1_EXTERNAL2, SPI6_CS2_EXTERNAL2, SPI6_CS3_EXTERNAL2} - - -/* I2C busses */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_ONBOARD 3 -#define PX4_I2C_BUS_EXPANSION2 4 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - -#define BOARD_NUMBER_I2C_BUSES 4 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} - /* * ADC channels * diff --git a/boards/holybro/kakutef7/src/board_config.h b/boards/holybro/kakutef7/src/board_config.h index 2fa2d6a0f7..2822eddb43 100644 --- a/boards/holybro/kakutef7/src/board_config.h +++ b/boards/holybro/kakutef7/src/board_config.h @@ -64,46 +64,6 @@ #define FLASH_BASED_PARAMS -/* SPI busses - */ -#define PX4_SPI_BUS_SD_CARD 1 -#define PX4_SPI_BUS_OSD 2 -#define PX4_SPI_BUS_SENSORS 4 - -#include - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -#define GPIO_SPI1_CS1_SD_CARD /* PA4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) - -#define PX4_SD_CARD_BUS_CS_GPIO {GPIO_SPI1_CS1_SD_CARD} - -#define GPIO_SPI2_CS1_OSD /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12) -#define PX4_SPIDEV_OSD PX4_MK_SPI_SEL(0,DRV_OSD_DEVTYPE_ATXXXX) - -#define PX4_OSD_BUS_CS_GPIO {GPIO_SPI2_CS1_OSD} - -/* SPI 4 CS (SPI4_SS) */ - -#define GPIO_SPI4_CS1_ICM20689 /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) - - -/* Define the SPI4 Data Ready interrupts */ - -#define GPIO_SPI4_DRDY1_ICM20689 /* PE1 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN1) - - -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20689) -#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI4_CS1_ICM20689} - -/* I2C busses */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - -#define BOARD_NUMBER_I2C_BUSES 1 -#define BOARD_I2C_BUS_CLOCK_INIT {100000} /* * ADC channels diff --git a/boards/intel/aerofc-v1/src/board_config.h b/boards/intel/aerofc-v1/src/board_config.h index 6359fec1e9..ea265027ce 100644 --- a/boards/intel/aerofc-v1/src/board_config.h +++ b/boards/intel/aerofc-v1/src/board_config.h @@ -71,26 +71,7 @@ #define GPIO_FORCE_BOOTLOADER (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN11|GPIO_EXTI) -/* - * I2C busses - * - * Peripheral Port - * I2C1_SDA PB9 - * I2C1_SCL PB8 - * - * I2C3_SDA PC9 - * I2C3_SCL PA8 - * - */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_ONBOARD 3 - -#include -#define GPIO_SPI_CS_MPU6500 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) +#define PX4_I2C_BUS_MTD 3 /* * STM32 ADC channels diff --git a/boards/modalai/fc-v1/init/rc.board_sensors b/boards/modalai/fc-v1/init/rc.board_sensors index 73140e1743..8046bd510e 100644 --- a/boards/modalai/fc-v1/init/rc.board_sensors +++ b/boards/modalai/fc-v1/init/rc.board_sensors @@ -13,7 +13,7 @@ voxlpm -X -b 3 -T P5VDC start mpu6000 -R 6 -s -T 20602 start # Internal SPI bus ICM-42688 -icm42688p -R 12 start +icm42688p -R 12 -s start # Internal SPI bus BMI088 accel bmi088 -A -R 4 -s start diff --git a/boards/modalai/fc-v1/src/board_config.h b/boards/modalai/fc-v1/src/board_config.h index fb5f597139..c79fe81951 100644 --- a/boards/modalai/fc-v1/src/board_config.h +++ b/boards/modalai/fc-v1/src/board_config.h @@ -77,141 +77,14 @@ # define BOARD_ARMED_STATE_LED LED_BLUE #endif -/* SPI - * - * SPI1 is sensors1 - * ICM-20602 - * CS PI9 - * DRDY PF2 - * - * SPI2 is sensors2 - * ICM-42688 - * CS PH5 - * DRDY PH12 - * - * SPI3 is not used - * - * SPI4 is not used - * - * SPI5 is FRAM - * FM25V02A - * CS PG7 - * - * SPI6 is sensors3 - * BMI088 - * CS1 PI10 - * CS2 PA15 - * DRDY1 PI6 - * DRDY2 PI7 - */ - -#define PX4_SPI_BUS_SENSORS1 1 -#define PX4_SPI_BUS_SENSORS2 2 -// SPI 3 not used -// SPI 4 not used -#define PX4_SPI_BUS_MEMORY 5 -#define PX4_SPI_BUS_SENSORS3 6 - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ - -#define GPIO_SPI1_nCS1_ICM20602 /* PI9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN9) - -/* Define the SPI1 Data Ready interrupts */ - -#define GPIO_SPI1_DRDY1_ICM20602 /* PF2 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN2) - -/* SPI1 off */ - -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20602) - -/* SPI 2 CS */ - -#define GPIO_SPI2_nCS1_ICM_42688 /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) - -/* Define the SPI2 Data Ready interrupts */ -#define GPIO_SPI2_DRDY1_ICM_42688 /* PH12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTH|GPIO_PIN12) // IMU_2_INT -> PH12 -#define GPIO_SPI2_DRDY2_ICM_42688 /* PA0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0) // IMU_2_FSYNC <- PA0/TIM5_CH1 - -/* SPI2 off */ - -#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK) -#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO) -#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI) - -/* SPI 5 CS */ - -#define GPIO_SPI5_nCS1_FRAM /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN7) - -/* SPI 6 CS */ - -#define GPIO_SPI6_nCS1_BMI088 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) -#define GPIO_SPI6_nCS2_BMI088 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) - -/* Define the SPI6 Data Ready interrupts */ - -#define GPIO_SPI6_DRDY1_BMI088_INT1_ACCEL /* PI6 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN6) -#define GPIO_SPI6_DRDY2_BMI088_INT3_GYRO /* PI7 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN7) - -/* Define the SPI6 Data Ready interrupts */ - -#define GPIO_DRDY_OFF_SPI6_DRDY1_BMI088 _PIN_OFF(GPIO_SPI6_DRDY1_BMI088_INT1_ACCEL) -#define GPIO_DRDY_OFF_SPI6_DRDY2_BMI088 _PIN_OFF(GPIO_SPI6_DRDY2_BMI088_INT3_GYRO) - -/* SPI6 off */ - -#define GPIO_SPI6_SCK_OFF _PIN_OFF(GPIO_SPI6_SCK) -#define GPIO_SPI6_MISO_OFF _PIN_OFF(GPIO_SPI6_MISO) -#define GPIO_SPI6_MOSI_OFF _PIN_OFF(GPIO_SPI6_MOSI) - -#define GPIO_DRDY_OFF_SPI6_DRDY1 _PIN_OFF(GPIO_DRDY_OFF_SPI6_DRDY1_BMI088) -#define GPIO_DRDY_OFF_SPI6_DRDY2 _PIN_OFF(GPIO_DRDY_OFF_SPI6_DRDY2_BMI088) - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY - -#include - -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SENSORS1_BUS_CS_GPIO {GPIO_SPI1_nCS1_ICM20602} - -#define PX4_SPIDEV_ICM_42688 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM42688P) -#define PX4_SENSORS2_BUS_CS_GPIO {GPIO_SPI2_nCS1_ICM_42688} - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI5_nCS1_FRAM} - -#define PX4_SPIDEV_BMI088_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI088) -#define PX4_SPIDEV_BMI088_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI088) -#define PX4_SENSORS3_BUS_CS_GPIO {GPIO_SPI6_nCS2_BMI088, GPIO_SPI6_nCS1_BMI088} - /* I2C busses */ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_EXPANSION2 3 -#define PX4_I2C_BUS_ONBOARD 4 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* Devices on the onboard bus. * * Note that these are unshifted addresses. */ #define PX4_I2C_OBDEV_A71CH 0x49 -#define BOARD_NUMBER_I2C_BUSES 4 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} - #define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) #define GPIO_A71CH_nRST /* PH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN3) diff --git a/boards/mro/ctrl-zero-f7/src/board_config.h b/boards/mro/ctrl-zero-f7/src/board_config.h index fce51dcfd4..9935992abe 100644 --- a/boards/mro/ctrl-zero-f7/src/board_config.h +++ b/boards/mro/ctrl-zero-f7/src/board_config.h @@ -65,66 +65,6 @@ #define BOARD_OVERLOAD_LED LED_RED #define BOARD_ARMED_STATE_LED LED_BLUE -#define PX4_SPI_BUS_1 1 -#define PX4_SPI_BUS_2 2 -#define PX4_SPI_BUS_5 5 - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ -#define GPIO_SPI1_CS1_ICM20602 /* PC2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) -#define GPIO_SPI1_CS2_ICM20948 /* PE15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15) - -/* Define the SPI1 Data Ready interrupts */ -#define GPIO_SPI1_DRDY1_ICM20602 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_SPI1_DRDY2_ICM20948 /* PE12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12) - -/* SPI 2 CS */ -#define GPIO_SPI2_CS1_FRAM /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) -#define GPIO_SPI2_CS2_BARO /* PD7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) - -/* SPI 5 CS */ -#define GPIO_SPI5_CS1_BMI088_ACCEL /* PF6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN6) -#define GPIO_SPI5_CS2_BMI088_GYRO /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) - -/* SPI 5 BMI088 Data Ready interrupts */ -#define GPIO_DRDY_BMI088_INT1_ACCEL /* PF1 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN1) -#define GPIO_DRDY_BMI088_INT2_ACCEL /* PF2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN2) -#define GPIO_DRDY_BMI088_INT3_GYRO /* PF3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN3) -#define GPIO_DRDY_BMI088_INT4_GYRO /* PF4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN4) - -/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */ -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_2 -/* ^ END Legacy SPI defines TODO: fix this with enumeration */ - -#include -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_ICM_20948 PX4_MK_SPI_SEL(0,DRV_DEVTYPE_UNUSED) -#define PX4_SPI_BUS_1_CS_GPIO {GPIO_SPI1_CS1_ICM20602, GPIO_SPI1_CS2_ICM20948} - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0,DRV_BARO_DEVTYPE_DPS310) -#define PX4_SPI_BUS_2_CS_GPIO {GPIO_SPI2_CS1_FRAM, GPIO_SPI2_CS2_BARO} - -#define PX4_SPIDEV_BMI088_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI088) -#define PX4_SPIDEV_BMI088_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI088) -#define PX4_SPI_BUS_5_CS_GPIO {GPIO_SPI5_CS1_BMI088_ACCEL, GPIO_SPI5_CS2_BMI088_GYRO} - - -/* I2C busses */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - -#define BOARD_NUMBER_I2C_BUSES 1 -#define BOARD_I2C_BUS_CLOCK_INIT {100000} - /* * ADC channels * diff --git a/boards/mro/x21-777/src/board_config.h b/boards/mro/x21-777/src/board_config.h index ba3e5c0b70..bbf22cbd20 100644 --- a/boards/mro/x21-777/src/board_config.h +++ b/boards/mro/x21-777/src/board_config.h @@ -75,50 +75,6 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) #define BOARD_OVERLOAD_LED LED_RED -/* External interrupts but on board*/ -#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) - -/* Data ready pins but on board */ - -#define GPIO_EXTI_ICM_2060X_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -/* Data ready pins off */ -#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_EXTI_ICM_2060X_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -/* SPI1 off */ -#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5) -#define GPIO_SPI1_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN6) -#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN7) - -/* SPI1 chip selects off */ -#define GPIO_SPI_CS_ICM_2060X_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2) - -/* SPI chip selects */ -#define GPIO_SPI_CS_ICM_2060X (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) -#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ -#include -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) - -/* I2C busses */ - -/* There is no I2C2 so there is not notion of internal / external*/ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* * ADC channels * diff --git a/boards/mro/x21/src/board_config.h b/boards/mro/x21/src/board_config.h index f97a8265af..605ec66c8b 100644 --- a/boards/mro/x21/src/board_config.h +++ b/boards/mro/x21/src/board_config.h @@ -73,50 +73,6 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) #define BOARD_OVERLOAD_LED LED_RED -/* External interrupts but on board*/ -#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) - -/* Data ready pins but on board */ - -#define GPIO_EXTI_ICM_2060X_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -/* Data ready pins off */ -#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_EXTI_ICM_2060X_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -/* SPI1 off */ -#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5) -#define GPIO_SPI1_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN6) -#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN7) - -/* SPI1 chip selects off */ -#define GPIO_SPI_CS_ICM_2060X_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2) - -/* SPI chip selects */ -#define GPIO_SPI_CS_ICM_2060X (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) -#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ -#include -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) - -/* I2C busses */ - -/* There is no I2C2 so there is not notion of internal / external*/ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* * ADC channels * diff --git a/boards/mro/x21/src/init.c b/boards/mro/x21/src/init.c index 46379a277d..711e1eb028 100644 --- a/boards/mro/x21/src/init.c +++ b/boards/mro/x21/src/init.c @@ -279,9 +279,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi1, 10000000); SPI_SETBITS(spi1, 8); SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, PX4_SPIDEV_ICM_20608, false); - SPI_SELECT(spi1, PX4_SPIDEV_BARO, false); - SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); up_udelay(20); /* Get the SPI port for the FRAM */ diff --git a/boards/nxp/fmuk66-v3/src/board_config.h b/boards/nxp/fmuk66-v3/src/board_config.h index 543bf72f65..0d25a91c52 100644 --- a/boards/nxp/fmuk66-v3/src/board_config.h +++ b/boards/nxp/fmuk66-v3/src/board_config.h @@ -191,31 +191,6 @@ __END_DECLS //#define GPIO_SD_CARDDETECT (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTD | PIN10) -/* SPI - * - * SD Card is on SPI 0 - * FXOS8700CQ Accelerometer & Magnetometer is on SPI 1 - * FXAS21002CQ Gyro is on SPI 2 - */ - -/* SPI Bus assignments */ - -#define PX4_SPI_BUS_MEMORY PX4_BUS_NUMBER_TO_PX4(0) -#define PX4_SPI_BUS_SENSORS PX4_BUS_NUMBER_TO_PX4(1) -#define PX4_SPI_BUS_EXTERNAL PX4_BUS_NUMBER_TO_PX4(2) -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY -#define PX4_SPI_BUS_EXT PX4_SPI_BUS_EXTERNAL - - -/* SPI chip selects */ - -#define GPIO_SPI_CS_MEMORY (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN2) -#define GPIO_SPI_CS_FXAS21002CQ_GYRO (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN9) -#define GPIO_SPI_CS_FXOS8700CQ_ACCEL_MAG (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN10) -#define GPIO_SPI1_CS_CALMEM (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN19) -#define GPIO_SPI2_CS (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN20) -#define GPIO_SPI2_EXT (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN15) - /* SPI device reset signals * In Active state */ @@ -233,41 +208,6 @@ __END_DECLS #define GPIO_EXTI_BARO_INT1 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTD | PIN11) #define GPIO_EXTI_BARO_INT2 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTD | PIN7) -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ - -#include -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI_CS_MEMORY} -#define PX4_MEMORY_BUS_FIRST_CS PX4_SPIDEV_MEMORY -#define PX4_MEMORY_BUS_LAST_CS PX4_SPIDEV_MEMORY - -#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_FXOS8701C) -#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_FXAS2100C) -#define PX4_SPIDEV_CALMEM PX4_MK_SPI_SEL(0,DRV_DEVTYPE_UNUSED) -#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI_CS_FXOS8700CQ_ACCEL_MAG, GPIO_SPI_CS_FXAS21002CQ_GYRO, GPIO_SPI1_CS_CALMEM} -#define PX4_SENSOR_BUS_FIRST_CS PX4_SPIDEV_ACCEL_MAG -#define PX4_SENSOR_BUS_LAST_CS PX4_SPIDEV_CALMEM - -#define PX4_SPIDEV_EXTERNAL1 PX4_MK_SPI_SEL(0,0) -#define PX4_SPIDEV_EXTERNAL2 PX4_MK_SPI_SEL(0,1) -#define PX4_EXTERNAL_BUS_CS_GPIO {GPIO_SPI2_CS, GPIO_SPI2_EXT} -#define PX4_EXTERNAL_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL1 -#define PX4_EXTERNAL_BUS_LAST_CS PX4_SPIDEV_EXTERNAL2 - -#define PX4_SPIDEV_ICM_20602 PX4_SPIDEV_EXTERNAL1 -#define PX4_SPIDEV_ICM_20608 PX4_SPIDEV_EXTERNAL1 -#define PX4_SPIDEV_ICM_20689 PX4_SPIDEV_EXTERNAL1 -#define PX4_SPIDEV_EXT_MPU PX4_SPIDEV_EXTERNAL1 -#define PX4_SPIDEV_MPU PX4_SPIDEV_EXTERNAL1 - -/* I2C busses */ - -#define PX4_I2C_BUS_ONBOARD PX4_BUS_NUMBER_TO_PX4(1) -#define PX4_I2C_BUS_EXPANSION PX4_BUS_NUMBER_TO_PX4(0) - - -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* * ADC channels * diff --git a/boards/nxp/fmurt1062-v1/default.cmake b/boards/nxp/fmurt1062-v1/default.cmake index 12d5a6ad50..92afa69022 100644 --- a/boards/nxp/fmurt1062-v1/default.cmake +++ b/boards/nxp/fmurt1062-v1/default.cmake @@ -25,9 +25,9 @@ px4_add_board( distance_sensor # all available distance sensor drivers # dshot not ported gps - imu/adis16448 - imu/adis16477 - imu/adis16497 + #imu/adis16448 + #imu/adis16477 + #imu/adis16497 #imu # all available imu drivers imu/bmi055 imu/mpu6000 diff --git a/boards/nxp/fmurt1062-v1/src/board_config.h b/boards/nxp/fmurt1062-v1/src/board_config.h index 7f25b5192a..ad3eafa7b2 100644 --- a/boards/nxp/fmurt1062-v1/src/board_config.h +++ b/boards/nxp/fmurt1062-v1/src/board_config.h @@ -90,16 +90,6 @@ #define BOARD_OVERLOAD_LED LED_RED #define BOARD_ARMED_STATE_LED LED_BLUE -/* SENSORS are on SPI1, 3 - * MEMORY is on bus SPI2 - * MS5611 is on bus SPI4 - */ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_MEMORY 2 -#define PX4_SPI_BUS_BARO 3 -#define PX4_SPI_BUS_EXTERNAL1 4 - /* * Define the ability to shut off off the sensor signals * by changing the signals to inputs @@ -112,24 +102,6 @@ #define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST) #define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) -/* SPI 1 CS */ -#define GPIO_SPI1_CS1_ICM20689 /* GPIO_EMC_40 GPIO3_IO26 */ (GPIO_PORT3 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) -// GPIO_SPI1_CS2_ICM20602 is not wired from CPU -#define GPIO_SPI1_CS3_BMI055_GYRO /* GPIO_B1_10 GPIO2_IO26 */ (GPIO_PORT2 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) -#define GPIO_SPI1_CS4_BMI055_ACCEL /* GPIO_B1_15 GPIO2_IO31 */ (GPIO_PORT2 | GPIO_PIN31 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) - -#define SPI1_CS5_AUX_MEM /* GPIO_SD_B1_00 GPIO3_IO00 */ (GPIO_PORT3 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) - -/* Define the SPI1 Data Ready interrupts */ - -#define DRDY_IOMUX (IOMUX_SCHMITT_TRIGGER | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ) - -// todo add IRQ-ness! - -#define GPIO_SPI1_DRDY1_ICM20689 /* GPIO_EMC_15 GPIO4_IO15 */ (GPIO_PORT4 | GPIO_PIN15 | GPIO_INPUT | DRDY_IOMUX) -#define GPIO_SPI1_DRDY2_BMI055_GYRO /* GPIO_EMC_16 GPIO4_IO16 */ (GPIO_PORT4 | GPIO_PIN16 | GPIO_INPUT | DRDY_IOMUX) -#define GPIO_SPI1_DRDY3_BMI055_ACCEL /* GPIO_EMC_37 GPIO3_IO23 */ (GPIO_PORT3 | GPIO_PIN23 | GPIO_INPUT | DRDY_IOMUX) -#define SPI1_DRDY4_ICM20602 /* GPIO_EMC_12 GPIO4_IO12 N.B . The ICM20602 CS is not wired */ (GPIO_PORT4 | GPIO_PIN12 | GPIO_INPUT | DRDY_IOMUX) /* SPI1 off */ @@ -141,19 +113,6 @@ #define GPIO_SPI1_MISO_OFF _PIN_OFF(_GPIO_LPSPI1_MISO) #define GPIO_SPI1_MOSI_OFF _PIN_OFF(_GPIO_LPSPI1_MOSI) -#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20689) -#define GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO _PIN_OFF(GPIO_SPI1_DRDY2_BMI055_GYRO) -#define GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC _PIN_OFF(GPIO_SPI1_DRDY3_BMI055_ACCEL) -#define GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY4_ICM20602) - -/* SPI 2 CS */ - -#define GPIO_SPI2_CS_FRAM /* GPIO_EMC_34 G GPIO3_IO20 */ (GPIO_PORT3 | GPIO_PIN20 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) - -/* SPI 3 CS */ - -#define GPIO_SPI3_CS1_MS5611 /* GPIO_EMC_14 GPIO4_IO14 */ (GPIO_PORT4 | GPIO_PIN14 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) - #define _GPIO_LPSPI3_SCK /* GPIO_AD_B1_15 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN31 | CS_IOMUX) #define _GPIO_LPSPI3_MISO /* GPIO_AD_B1_13 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN29 | CS_IOMUX) #define _GPIO_LPSPI3_MOSI /* GPIO_AD_B1_14 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN30 | CS_IOMUX) @@ -162,12 +121,6 @@ #define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO) #define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI) -/* SPI 4 CS */ - -#define SPI4_CS1_EXTERNAL1 /* GPIO_EMC_07 GPIO4_IO07 */ (GPIO_PORT4 | GPIO_PIN7 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) -#define SPI4_CS2_EXTERNAL1 /* GPIO_B1_14 GPIO2_IO30 */ (GPIO_PORT2 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) -#define SPI4_CS3_EXTERNAL1 /* GPIO_EMC_11 GPIO4_IO011 */ (GPIO_PORT4 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX) - /* Define the SPI4 Data Ready and Control signals */ #define GPIO_SPI4_DRDY7_EXTERNAL1 /* GPIO_EMC_35 GPIO3_IO21*/ (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX) @@ -179,52 +132,6 @@ #define GPIO_SPI4_SYNC_EXTERNAL1_OFF _PIN_OFF(GPIO_SPI4_SYNC_EXTERNAL1) -/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */ - -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY -#define PX4_SPIDEV_BMA 0 -#define PX4_SPIDEV_BMI 0 - -/* ^ END Legacy SPI defines TODO: fix this with enumeration */ -#include - -#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20689) -#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI055) -#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI055) -#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(0,DRV_DEVTYPE_UNUSED) - -#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS3_BMI055_GYRO, GPIO_SPI1_CS4_BMI055_ACCEL, SPI1_CS5_AUX_MEM} -#define PX4_SENSORS_BUS_FIRST_CS PX4_SPIDEV_ICM_20689 -#define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_AUX_MEM - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI2_CS_FRAM} -#define PX4_MEMORY_BUS_FIRST_CS PX4_SPIDEV_MEMORY -#define PX4_MEMORY_BUS_LAST_CS PX4_SPIDEV_MEMORY - -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0,DRV_BARO_DEVTYPE_MS5611) -#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI3_CS1_MS5611} -#define PX4_BARO_BUS_FIRST_CS PX4_SPIDEV_BARO -#define PX4_BARO_BUS_LAST_CS PX4_SPIDEV_BARO - -#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(0,0) -#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(0,1) -#define PX4_SPIDEV_EXTERNAL1_3 PX4_MK_SPI_SEL(0,2) -#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI4_CS1_EXTERNAL1, SPI4_CS2_EXTERNAL1, SPI4_CS3_EXTERNAL1} -#define PX4_EXTERNAL1_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL1_1 -#define PX4_EXTERNAL1_BUS_LAST_CS PX4_SPIDEV_EXTERNAL1_3 - -/* I2C busses */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_ONBOARD 3 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - -#define BOARD_NUMBER_I2C_BUSES 3 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000} - - #define ADC_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) #define ADC1_CH(n) (n) diff --git a/boards/nxp/rddrone-uavcan146/src/CMakeLists.txt b/boards/nxp/rddrone-uavcan146/src/CMakeLists.txt index 497340528e..ed22122425 100644 --- a/boards/nxp/rddrone-uavcan146/src/CMakeLists.txt +++ b/boards/nxp/rddrone-uavcan146/src/CMakeLists.txt @@ -37,6 +37,7 @@ add_library(drivers_board bringup.c buttons.c clockconfig.c + i2c.cpp init.c periphclocks.c spi.c diff --git a/boards/nxp/rddrone-uavcan146/src/board_config.h b/boards/nxp/rddrone-uavcan146/src/board_config.h index db48f2b8ea..d72c6fa944 100644 --- a/boards/nxp/rddrone-uavcan146/src/board_config.h +++ b/boards/nxp/rddrone-uavcan146/src/board_config.h @@ -94,10 +94,6 @@ __BEGIN_DECLS #define NUM_OF_PERIPHERAL_CLOCKS_0 15 -/* I2C busses */ - -#define PX4_I2C_BUS_ONBOARD PX4_BUS_NUMBER_TO_PX4(1) -#define PX4_I2C_BUS_EXPANSION PX4_BUS_NUMBER_TO_PX4(0) /**************************************************************************** * Public Types diff --git a/boards/nxp/rddrone-uavcan146/src/i2c.cpp b/boards/nxp/rddrone-uavcan146/src/i2c.cpp new file mode 100644 index 0000000000..cff9faf052 --- /dev/null +++ b/boards/nxp/rddrone-uavcan146/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(1)), + initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(0)), +}; + diff --git a/boards/omnibus/f4sd/src/board_config.h b/boards/omnibus/f4sd/src/board_config.h index e0c7fe57ce..72e7051e77 100644 --- a/boards/omnibus/f4sd/src/board_config.h +++ b/boards/omnibus/f4sd/src/board_config.h @@ -108,93 +108,12 @@ //#define GPIO_GPIO4_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM5_CH2OUT) //#define GPIO_GPIO5_OUTPUT _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT) -/*----------------------------------------------------------*/ -/* OMNIBUSF4SD SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -#include - -/* SPI chip selects */ -/* - * Define the Chip Selects for SPI1 - * - * MPU6000: PA4 - * - */ -#define GPIO_SPI_CS_MEMS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) - -/* - * Define the Chip Selects for SPI2 - * - * SD Card: PB12 - * - */ -#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12) - -/* - * Define the Chip Selects for SPI3 - * - * BMP280: PB3 - * ABT7456: PA15 - * - */ - -#define GPIO_SPI3_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN3) -#define GPIO_SPI3_CS_OSD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - -/* SPI 1 bus off */ -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) -/* SPI 1 CS's off */ -#define GPIO_SPI1_CS_MEMS_OFF _PIN_OFF(GPIO_SPI_CS_MEMS) - -/* SPI 2 bus off */ -#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK) -#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO) -#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI) -/* SPI 2 CS's off */ -#define GPIO_SPI2_CS_SDCARD_OFF _PIN_OFF(GPIO_SPI_CS_SDCARD) - -/* SPI 3 bus off */ -#define GPIO_SPI3_SCK_OFF _PIN_OFF(GPIO_SPI3_SCK) -#define GPIO_SPI3_MISO_OFF _PIN_OFF(GPIO_SPI3_MISO) -#define GPIO_SPI3_MOSI_OFF _PIN_OFF(GPIO_SPI3_MOSI) -/* SPI 3 CS's off */ -#define GPIO_SPI3_CS_BARO_OFF _PIN_OFF(GPIO_SPI3_CS_BARO) -#define GPIO_SPI3_CS_OSD_OFF _PIN_OFF(GPIO_SPI3_CS_OSD) - -// One device per bus -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_BARO_BUS 3 -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_BMP280) -#define PX4_SPIDEV_OSD PX4_MK_SPI_SEL(0, DRV_OSD_DEVTYPE_ATXXXX) - /* USB OTG FS * * PA9 OTG_FS_VBUS VBUS sensing */ #define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTC|GPIO_PIN5) -/*----------------------------------------------------------*/ -/* End OMNIBUSF4SD SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -#define PX4_SPI_BUS_BARO 3 -#define PX4_SPI_BUS_OSD 3 - -#define PX4_I2C_BUS_EXPANSION 2 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* PWM * * Alternatively CH3/CH4 could be assigned to UART6_TX/RX diff --git a/boards/omnibus/f4sd/src/init.c b/boards/omnibus/f4sd/src/init.c index fc27d3a660..ed5f2a95e2 100644 --- a/boards/omnibus/f4sd/src/init.c +++ b/boards/omnibus/f4sd/src/init.c @@ -284,7 +284,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi1, 10000000); SPI_SETBITS(spi1, 8); SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); up_udelay(20); // SPI2: SDCard @@ -327,7 +326,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi3, 10 * 1000 * 1000); SPI_SETBITS(spi3, 8); SPI_SETMODE(spi3, SPIDEV_MODE3); - SPI_SELECT(spi3, PX4_SPIDEV_BARO, false); up_udelay(20); #if defined(FLASH_BASED_PARAMS) diff --git a/boards/px4/fmu-v2/src/board_config.h b/boards/px4/fmu-v2/src/board_config.h index 2957922f5d..0ef74dad9b 100644 --- a/boards/px4/fmu-v2/src/board_config.h +++ b/boards/px4/fmu-v2/src/board_config.h @@ -88,271 +88,12 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) #define BOARD_OVERLOAD_LED LED_AMBER -#include - -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * Only the GPIO_SPIb_xxx_Ppi will be used in the code to insure this are no - * cross connections. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv2: FmuV3 Cube PixhawkMini - * Power Domain: VDD_3V3_SENSORS_EN nVDD_5V_PERIPH_EN V3V:SPI1&SPI4 V3V:SPI1 No SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 GYRO_DRDY SPI4:EXTERN_DRDY NC - * PB1 MAG_DRDY +SPI4:nEXTERN_CS NC - * PB4 ACCEL_DRDY NC NC - * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS - * PC2 nMPU_CS @MPU6000|MPU9250 @MPU9250 - * PC13 nGYRO_CS SPI4:nGYRO_EXT_CS NC - * PC14 GPIO_EXT_1 nBARO_EXT_CS -20608_DRDY - * PC15 nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS 20608_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000|MPU9250 @MPU9250 - * PE2 SPI_EXT_SCK NC - * PE4 nSPI_EXT_NSS SPI4:nMPU_EXT_CS NC - * PE5 SPI_EXT_MISO NC - * PE6 SPI_EXT_MOSI NC - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - * The board API provides for mechanism to perform a SPI bus reset. - * To facilitate a SPI bus reset - * - * 1) All the pins: SPIn, CD, DRDY associated with the SPI bus are turned to inputs - * with outputs driven low. (OFFIng) - * 2) The power domain of that bus is turned off. - * 3) A usleep it done for ms. - * 4) The power domain of that bus is turned back on. - * 5) The SPIn pins are re-initialized. - * 6) The SPI CS, DRDY pins are re-initialized. - * - * To insure the complete net is de-energized and is not bing back fed, it is important to - * note the all signals in the net list of the parts/bus. - * - * I.E. Not OFFIng PC1 on V3 would leave that pin back feeding the HMC part. As would not - * OFFIng PE4, not associated with SPI1 on V2, but would back feed an MPUxxxx on V3 - * - */ - - -/*----------------------------------------------------------*/ -/* FMUv2 SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -/* FMUv2 SPI1 chip selects */ -/* PC1 Spare ADC IN10 */ -#define GPIO_SPI1_CS_PC2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) -#define GPIO_SPI1_CS_PC13 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) -#define GPIO_SPI1_CS_PC15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI1_CS_PD7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) - -/* FMUv2 SPI2 chip selects */ -#define GPIO_SPI2_CS_PD10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) - -/* FMUv2 SPI4 chip selects */ -#define GPIO_SPI4_GPIO_PC14 /* !V2M */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14) -#define GPIO_SPI4_NSS_PE4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) - -/* FMUv2 SPI1 chip selects Assignments */ - -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 -#define GPIO_SPI1_CS_GYRO GPIO_SPI1_CS_PC13 -#define GPIO_SPI1_CS_ACCEL_MAG GPIO_SPI1_CS_PC15 -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 - -/* FMUv2 SPI2 chip selects Assignments */ - -#define GPIO_SPI2_CS_FRAM GPIO_SPI2_CS_PD10 - -/* FMUv2 SPI4 chip selects Assignments */ - -#define GPIO_SPI4_GPIO_EXT GPIO_SPI4_GPIO_PC14 -#define GPIO_SPI4_EXT_NSS GPIO_SPI4_NSS_PE4 - -/* FMUv2 DRDY */ - -#define GPIO_SPI1_EXTI_DRDY_PB0 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0) -#define GPIO_SPI1_EXTI_DRDY_PB1 /*!V3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1) #define GPIO_SPI1_EXTI_DRDY_PB4 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_EXTI_DRDY_PD15 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) - -/* FMUv2 DRDY Assignments */ - -#define GPIO_SPI1_EXTI_GYRO_DRDY GPIO_SPI1_EXTI_DRDY_PB0 -#define GPIO_SPI1_EXTI_MAG_DRDY GPIO_SPI1_EXTI_DRDY_PB1 -#define GPIO_SPI1_EXTI_ACCEL_DRDY GPIO_SPI1_EXTI_DRDY_PB4 -#define GPIO_SPI1_EXTI_MPU_DRDY GPIO_SPI1_EXTI_DRDY_PD15 - -/*----------------------------------------------------------*/ -/* End FMUv2 SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_EXT 4 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - -/* Use these to select a specific SPI device on SPI1 */ - -#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_L3GD20) -#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(0, DRV_ACC_DEVTYPE_LSM303D) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) - -/* FMUv3 SPI on external bus */ - -#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_L3GD20) -#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(0, DRV_ACC_DEVTYPE_LSM303D) -#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_BMI055) - -/* I2C busses */ -#define BOARD_OVERRIDE_I2C_BUS_EXTERNAL -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_ONBOARD 2 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD #define BOARD_SPI_BUS_MAX_BUS_ITEMS 3 -/*----------------------------------------------------------*/ -/* FMUv3 Cube SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv3 Cube: FmuV2 PixhawkMini - * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1 No SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 EXTERN_DRDY SPI1:GYRO_DRDY NC - * PB1 MAG_DRDY nEXTERN_CS -SPI1:MAG_DRDY NC - * PB4 NC SPI1:ACCEL_DRDY NC - * PC1 SPI_INT_MAG_!CS -ADC1_IN11 NC - * PC2 nMPU_CS @MPU6000 @MPU9250 - * PC13 nGYRO_EXT_CS SPI1:nGYRO_CS NC - * PC14 nBARO_EXT_CS GPIO_EXT_1 -20608_DRDY - * PC15 nACCEL_MAG_EXT_CS SPI1:nACCEL_MAG_CS 20608_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000 @MPU9250 - * PE2 SPI_EXT_SCK NC - * PE4 MPU_EXT_CS SPI4:nSPI_EXT_NSS NC - * PE5 SPI_EXT_MISO NC - * PE6 SPI_EXT_MOSI NC - * - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - */ - -/* FMUv3 Cube SPI1 chip selects */ -/* Was a spare ACD IN10 on V2 */ -#define GPIO_SPI1_CS_PC1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1) -#define GPIO_SPI4_CS_PB1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) -#define GPIO_SPI4_CS_PC13 GPIO_SPI1_CS_PC13 -#define GPIO_SPI4_CS_PC14 GPIO_SPI4_GPIO_PC14 -#define GPIO_SPI4_CS_PC15 GPIO_SPI1_CS_PC15 - -/* FMUv3 Cube chip selects Assignments */ -/* Cube 2.0 V2.1 */ -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 /* MPU600 MPU9250 */ -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 /* MS5611 MS5611 */ -#define GPIO_SPI1_CS_HMC GPIO_SPI1_CS_PC1 /* HMC5983 Removed */ - -/* N.B. bus moves from SPI1 to SPI4 */ -#define GPIO_SPI4_GYRO_EXT_CS GPIO_SPI4_CS_PC13 -#define GPIO_SPI4_BARO_EXT_CS GPIO_SPI4_CS_PC14 -#define GPIO_SPI4_ACCEL_MAG_EXT_CS GPIO_SPI4_CS_PC15 - -/* No move */ -#define GPIO_SPI4_MPU_EXT_CS GPIO_SPI4_NSS_PE4 - -/* FMUv3 DRDY Assignments */ -#define GPIO_SPI4_EXTI_DRDY_PB0 GPIO_SPI1_EXTI_DRDY_PB0 -#define GPIO_SPI4_EXTI_EXTERN_DRDY GPIO_SPI4_EXTI_DRDY_PB0 -#define GPIO_SPI4_EXTERN_CS GPIO_SPI4_CS_PB1 -/* PB1 is an External CS on V3 */ - -#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_HMC5883) - -/*----------------------------------------------------------*/ -/* End FMUv3 Cube SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ -/*----------------------------------------------------------*/ -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv2 Pixhawk Mini FmuV2 FmuV3 Cube - * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1&SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 NC SPI1:GYRO_DRDY SPI4:EXTERN_DRDY - * PB1 NC -SPI1:MAG_DRDY +SPI4:nEXTERN_CS - * PB4 NC SPI1:ACCEL_DRDY NC - * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS - * PC2 nMPU_CS @MPU6000 @MPU6000|MPU9250 - * PC13 NC SPI1:nGYRO_CS SPI4:nGYRO_EXT_CS - * PC14 20608_DRDY +GPIO_EXT_1 nBARO_EXT_CS - * PC15 20608_CS nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000 @MPU6000|MPU9250 - * PE2 NC SPI_EXT_SCK SPI_EXT_SCK - * PE4 NC SPI4:nSPI_EXT_NSS SPI4:nMPU_EXT_CS - * PE5 NC SPI_EXT_MISO SPI_EXT_MISO - * PE6 NC SPI_EXT_MOSI SPI_EXT_MOSI - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - */ - -/*----------------------------------------------------------*/ -/* FMUv2 PixhawkMini SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -/* FMUv2 PixhawkMini SPI1 chip selects */ - -/* FMUv3 Cube chip selects Assignments */ - -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 /* MPU9250 */ -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 /* MS5611 */ -#define GPIO_SPI1_CS_20608 GPIO_SPI1_CS_PC15 /* ICM20608 */ - -/* FMUv3 DRDY Assignments */ - -/* Pixhawk mini has reused the PC14 GPIO_SPI_CS_EXT1 signal that was associated - * with SPI4. - */ -#define GPIO_SPI1_EXTI_20608_DRDY_PC14 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) - - +/* I2C busses */ +#define BOARD_OVERRIDE_I2C_BUS_EXTERNAL /* * ADC channels diff --git a/boards/px4/fmu-v2/src/spi.cpp b/boards/px4/fmu-v2/src/spi.cpp index 74f3c19923..ff1013c065 100644 --- a/boards/px4/fmu-v2/src/spi.cpp +++ b/boards/px4/fmu-v2/src/spi.cpp @@ -35,6 +35,116 @@ #include #include +/* Due to inconsistent use of chip select and data ready signal on + * different board that use this build, we are using different + * versions. + * + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv2: FmuV3 Cube PixhawkMini + * Power Domain: VDD_3V3_SENSORS_EN nVDD_5V_PERIPH_EN V3V:SPI1&SPI4 V3V:SPI1 No SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 GYRO_DRDY SPI4:EXTERN_DRDY NC + * PB1 MAG_DRDY +SPI4:nEXTERN_CS NC + * PB4 ACCEL_DRDY NC NC + * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS + * PC2 nMPU_CS @MPU6000|MPU9250 @MPU9250 + * PC13 nGYRO_CS SPI4:nGYRO_EXT_CS NC + * PC14 GPIO_EXT_1 nBARO_EXT_CS -20608_DRDY + * PC15 nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS 20608_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000|MPU9250 @MPU9250 + * PE2 SPI_EXT_SCK NC + * PE4 nSPI_EXT_NSS SPI4:nMPU_EXT_CS NC + * PE5 SPI_EXT_MISO NC + * PE6 SPI_EXT_MOSI NC + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + * The board API provides for mechanism to perform a SPI bus reset. + * To facilitate a SPI bus reset + * + * 1) All the pins: SPIn, CD, DRDY associated with the SPI bus are turned to inputs + * with outputs driven low. (OFFIng) + * 2) The power domain of that bus is turned off. + * 3) A usleep it done for ms. + * 4) The power domain of that bus is turned back on. + * 5) The SPIn pins are re-initialized. + * 6) The SPI CS, DRDY pins are re-initialized. + * + * To insure the complete net is de-energized and is not bing back fed, it is important to + * note the all signals in the net list of the parts/bus. + * + * I.E. Not OFFIng PC1 on V3 would leave that pin back feeding the HMC part. As would not + * OFFIng PE4, not associated with SPI1 on V2, but would back feed an MPUxxxx on V3 + * + */ + +/* + * + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv3 Cube: FmuV2 PixhawkMini + * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1 No SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 EXTERN_DRDY SPI1:GYRO_DRDY NC + * PB1 MAG_DRDY nEXTERN_CS -SPI1:MAG_DRDY NC + * PB4 NC SPI1:ACCEL_DRDY NC + * PC1 SPI_INT_MAG_!CS -ADC1_IN11 NC + * PC2 nMPU_CS @MPU6000 @MPU9250 + * PC13 nGYRO_EXT_CS SPI1:nGYRO_CS NC + * PC14 nBARO_EXT_CS GPIO_EXT_1 -20608_DRDY + * PC15 nACCEL_MAG_EXT_CS SPI1:nACCEL_MAG_CS 20608_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000 @MPU9250 + * PE2 SPI_EXT_SCK NC + * PE4 MPU_EXT_CS SPI4:nSPI_EXT_NSS NC + * PE5 SPI_EXT_MISO NC + * PE6 SPI_EXT_MOSI NC + * + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + */ + +/*----------------------------------------------------------*/ +/* + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv2 Pixhawk Mini FmuV2 FmuV3 Cube + * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1&SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 NC SPI1:GYRO_DRDY SPI4:EXTERN_DRDY + * PB1 NC -SPI1:MAG_DRDY +SPI4:nEXTERN_CS + * PB4 NC SPI1:ACCEL_DRDY NC + * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS + * PC2 nMPU_CS @MPU6000 @MPU6000|MPU9250 + * PC13 NC SPI1:nGYRO_CS SPI4:nGYRO_EXT_CS + * PC14 20608_DRDY +GPIO_EXT_1 nBARO_EXT_CS + * PC15 20608_CS nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000 @MPU6000|MPU9250 + * PE2 NC SPI_EXT_SCK SPI_EXT_SCK + * PE4 NC SPI4:nSPI_EXT_NSS SPI4:nMPU_EXT_CS + * PE5 NC SPI_EXT_MISO SPI_EXT_MISO + * PE6 NC SPI_EXT_MOSI SPI_EXT_MOSI + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + */ + constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { initSPIHWVersion(HW_VER_FMUV2, { initSPIBus(SPI::Bus::SPI1, { diff --git a/boards/px4/fmu-v3/src/board_config.h b/boards/px4/fmu-v3/src/board_config.h index 2957922f5d..0ef74dad9b 100644 --- a/boards/px4/fmu-v3/src/board_config.h +++ b/boards/px4/fmu-v3/src/board_config.h @@ -88,271 +88,12 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) #define BOARD_OVERLOAD_LED LED_AMBER -#include - -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * Only the GPIO_SPIb_xxx_Ppi will be used in the code to insure this are no - * cross connections. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv2: FmuV3 Cube PixhawkMini - * Power Domain: VDD_3V3_SENSORS_EN nVDD_5V_PERIPH_EN V3V:SPI1&SPI4 V3V:SPI1 No SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 GYRO_DRDY SPI4:EXTERN_DRDY NC - * PB1 MAG_DRDY +SPI4:nEXTERN_CS NC - * PB4 ACCEL_DRDY NC NC - * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS - * PC2 nMPU_CS @MPU6000|MPU9250 @MPU9250 - * PC13 nGYRO_CS SPI4:nGYRO_EXT_CS NC - * PC14 GPIO_EXT_1 nBARO_EXT_CS -20608_DRDY - * PC15 nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS 20608_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000|MPU9250 @MPU9250 - * PE2 SPI_EXT_SCK NC - * PE4 nSPI_EXT_NSS SPI4:nMPU_EXT_CS NC - * PE5 SPI_EXT_MISO NC - * PE6 SPI_EXT_MOSI NC - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - * The board API provides for mechanism to perform a SPI bus reset. - * To facilitate a SPI bus reset - * - * 1) All the pins: SPIn, CD, DRDY associated with the SPI bus are turned to inputs - * with outputs driven low. (OFFIng) - * 2) The power domain of that bus is turned off. - * 3) A usleep it done for ms. - * 4) The power domain of that bus is turned back on. - * 5) The SPIn pins are re-initialized. - * 6) The SPI CS, DRDY pins are re-initialized. - * - * To insure the complete net is de-energized and is not bing back fed, it is important to - * note the all signals in the net list of the parts/bus. - * - * I.E. Not OFFIng PC1 on V3 would leave that pin back feeding the HMC part. As would not - * OFFIng PE4, not associated with SPI1 on V2, but would back feed an MPUxxxx on V3 - * - */ - - -/*----------------------------------------------------------*/ -/* FMUv2 SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -/* FMUv2 SPI1 chip selects */ -/* PC1 Spare ADC IN10 */ -#define GPIO_SPI1_CS_PC2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) -#define GPIO_SPI1_CS_PC13 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) -#define GPIO_SPI1_CS_PC15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI1_CS_PD7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) - -/* FMUv2 SPI2 chip selects */ -#define GPIO_SPI2_CS_PD10 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) - -/* FMUv2 SPI4 chip selects */ -#define GPIO_SPI4_GPIO_PC14 /* !V2M */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14) -#define GPIO_SPI4_NSS_PE4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) - -/* FMUv2 SPI1 chip selects Assignments */ - -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 -#define GPIO_SPI1_CS_GYRO GPIO_SPI1_CS_PC13 -#define GPIO_SPI1_CS_ACCEL_MAG GPIO_SPI1_CS_PC15 -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 - -/* FMUv2 SPI2 chip selects Assignments */ - -#define GPIO_SPI2_CS_FRAM GPIO_SPI2_CS_PD10 - -/* FMUv2 SPI4 chip selects Assignments */ - -#define GPIO_SPI4_GPIO_EXT GPIO_SPI4_GPIO_PC14 -#define GPIO_SPI4_EXT_NSS GPIO_SPI4_NSS_PE4 - -/* FMUv2 DRDY */ - -#define GPIO_SPI1_EXTI_DRDY_PB0 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0) -#define GPIO_SPI1_EXTI_DRDY_PB1 /*!V3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1) #define GPIO_SPI1_EXTI_DRDY_PB4 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_EXTI_DRDY_PD15 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) - -/* FMUv2 DRDY Assignments */ - -#define GPIO_SPI1_EXTI_GYRO_DRDY GPIO_SPI1_EXTI_DRDY_PB0 -#define GPIO_SPI1_EXTI_MAG_DRDY GPIO_SPI1_EXTI_DRDY_PB1 -#define GPIO_SPI1_EXTI_ACCEL_DRDY GPIO_SPI1_EXTI_DRDY_PB4 -#define GPIO_SPI1_EXTI_MPU_DRDY GPIO_SPI1_EXTI_DRDY_PD15 - -/*----------------------------------------------------------*/ -/* End FMUv2 SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_EXT 4 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS - -/* Use these to select a specific SPI device on SPI1 */ - -#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_L3GD20) -#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(0, DRV_ACC_DEVTYPE_LSM303D) -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) - -/* FMUv3 SPI on external bus */ - -#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_L3GD20) -#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(0, DRV_ACC_DEVTYPE_LSM303D) -#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(0, DRV_GYR_DEVTYPE_BMI055) - -/* I2C busses */ -#define BOARD_OVERRIDE_I2C_BUS_EXTERNAL -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_ONBOARD 2 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD #define BOARD_SPI_BUS_MAX_BUS_ITEMS 3 -/*----------------------------------------------------------*/ -/* FMUv3 Cube SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv3 Cube: FmuV2 PixhawkMini - * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1 No SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 EXTERN_DRDY SPI1:GYRO_DRDY NC - * PB1 MAG_DRDY nEXTERN_CS -SPI1:MAG_DRDY NC - * PB4 NC SPI1:ACCEL_DRDY NC - * PC1 SPI_INT_MAG_!CS -ADC1_IN11 NC - * PC2 nMPU_CS @MPU6000 @MPU9250 - * PC13 nGYRO_EXT_CS SPI1:nGYRO_CS NC - * PC14 nBARO_EXT_CS GPIO_EXT_1 -20608_DRDY - * PC15 nACCEL_MAG_EXT_CS SPI1:nACCEL_MAG_CS 20608_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000 @MPU9250 - * PE2 SPI_EXT_SCK NC - * PE4 MPU_EXT_CS SPI4:nSPI_EXT_NSS NC - * PE5 SPI_EXT_MISO NC - * PE6 SPI_EXT_MOSI NC - * - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - */ - -/* FMUv3 Cube SPI1 chip selects */ -/* Was a spare ACD IN10 on V2 */ -#define GPIO_SPI1_CS_PC1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1) -#define GPIO_SPI4_CS_PB1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1) -#define GPIO_SPI4_CS_PC13 GPIO_SPI1_CS_PC13 -#define GPIO_SPI4_CS_PC14 GPIO_SPI4_GPIO_PC14 -#define GPIO_SPI4_CS_PC15 GPIO_SPI1_CS_PC15 - -/* FMUv3 Cube chip selects Assignments */ -/* Cube 2.0 V2.1 */ -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 /* MPU600 MPU9250 */ -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 /* MS5611 MS5611 */ -#define GPIO_SPI1_CS_HMC GPIO_SPI1_CS_PC1 /* HMC5983 Removed */ - -/* N.B. bus moves from SPI1 to SPI4 */ -#define GPIO_SPI4_GYRO_EXT_CS GPIO_SPI4_CS_PC13 -#define GPIO_SPI4_BARO_EXT_CS GPIO_SPI4_CS_PC14 -#define GPIO_SPI4_ACCEL_MAG_EXT_CS GPIO_SPI4_CS_PC15 - -/* No move */ -#define GPIO_SPI4_MPU_EXT_CS GPIO_SPI4_NSS_PE4 - -/* FMUv3 DRDY Assignments */ -#define GPIO_SPI4_EXTI_DRDY_PB0 GPIO_SPI1_EXTI_DRDY_PB0 -#define GPIO_SPI4_EXTI_EXTERN_DRDY GPIO_SPI4_EXTI_DRDY_PB0 -#define GPIO_SPI4_EXTERN_CS GPIO_SPI4_CS_PB1 -/* PB1 is an External CS on V3 */ - -#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_HMC5883) - -/*----------------------------------------------------------*/ -/* End FMUv3 Cube SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ -/*----------------------------------------------------------*/ -/* Due to inconsistent use of chip select and dry signal on - * different board that use this build. We are defining the GPIO - * inclusive of the SPI port and GPIO to help identify pins the - * are part of the sensor Net's controlled by different power - * domains. - * - * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- - * FMUv2 Pixhawk Mini FmuV2 FmuV3 Cube - * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1&SPI4 - * PA5 SPI_INT_SCK - * PA6 SPI_INT_MISO - * PA7 SPI_INT_MOSI - * PB0 NC SPI1:GYRO_DRDY SPI4:EXTERN_DRDY - * PB1 NC -SPI1:MAG_DRDY +SPI4:nEXTERN_CS - * PB4 NC SPI1:ACCEL_DRDY NC - * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS - * PC2 nMPU_CS @MPU6000 @MPU6000|MPU9250 - * PC13 NC SPI1:nGYRO_CS SPI4:nGYRO_EXT_CS - * PC14 20608_DRDY +GPIO_EXT_1 nBARO_EXT_CS - * PC15 20608_CS nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS - * PD7 nBARO_CS - * PD15 nMPU_DRDY @MPU6000 @MPU6000|MPU9250 - * PE2 NC SPI_EXT_SCK SPI_EXT_SCK - * PE4 NC SPI4:nSPI_EXT_NSS SPI4:nMPU_EXT_CS - * PE5 NC SPI_EXT_MISO SPI_EXT_MISO - * PE6 NC SPI_EXT_MOSI SPI_EXT_MOSI - * - * Notes: Prefixed with @ Does not effect board control - * Prefixed with + Input used as Output - * Prefixed with - Output used as Input - * Prefixed with SPIn: Bus changed - * - */ - -/*----------------------------------------------------------*/ -/* FMUv2 PixhawkMini SPI chip selects and DRDY */ -/*----------------------------------------------------------*/ - -/* FMUv2 PixhawkMini SPI1 chip selects */ - -/* FMUv3 Cube chip selects Assignments */ - -#define GPIO_SPI1_CS_MPU GPIO_SPI1_CS_PC2 /* MPU9250 */ -#define GPIO_SPI1_CS_BARO GPIO_SPI1_CS_PD7 /* MS5611 */ -#define GPIO_SPI1_CS_20608 GPIO_SPI1_CS_PC15 /* ICM20608 */ - -/* FMUv3 DRDY Assignments */ - -/* Pixhawk mini has reused the PC14 GPIO_SPI_CS_EXT1 signal that was associated - * with SPI4. - */ -#define GPIO_SPI1_EXTI_20608_DRDY_PC14 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) - - +/* I2C busses */ +#define BOARD_OVERRIDE_I2C_BUS_EXTERNAL /* * ADC channels diff --git a/boards/px4/fmu-v3/src/spi.cpp b/boards/px4/fmu-v3/src/spi.cpp index 74f3c19923..ff1013c065 100644 --- a/boards/px4/fmu-v3/src/spi.cpp +++ b/boards/px4/fmu-v3/src/spi.cpp @@ -35,6 +35,116 @@ #include #include +/* Due to inconsistent use of chip select and data ready signal on + * different board that use this build, we are using different + * versions. + * + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv2: FmuV3 Cube PixhawkMini + * Power Domain: VDD_3V3_SENSORS_EN nVDD_5V_PERIPH_EN V3V:SPI1&SPI4 V3V:SPI1 No SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 GYRO_DRDY SPI4:EXTERN_DRDY NC + * PB1 MAG_DRDY +SPI4:nEXTERN_CS NC + * PB4 ACCEL_DRDY NC NC + * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS + * PC2 nMPU_CS @MPU6000|MPU9250 @MPU9250 + * PC13 nGYRO_CS SPI4:nGYRO_EXT_CS NC + * PC14 GPIO_EXT_1 nBARO_EXT_CS -20608_DRDY + * PC15 nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS 20608_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000|MPU9250 @MPU9250 + * PE2 SPI_EXT_SCK NC + * PE4 nSPI_EXT_NSS SPI4:nMPU_EXT_CS NC + * PE5 SPI_EXT_MISO NC + * PE6 SPI_EXT_MOSI NC + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + * The board API provides for mechanism to perform a SPI bus reset. + * To facilitate a SPI bus reset + * + * 1) All the pins: SPIn, CD, DRDY associated with the SPI bus are turned to inputs + * with outputs driven low. (OFFIng) + * 2) The power domain of that bus is turned off. + * 3) A usleep it done for ms. + * 4) The power domain of that bus is turned back on. + * 5) The SPIn pins are re-initialized. + * 6) The SPI CS, DRDY pins are re-initialized. + * + * To insure the complete net is de-energized and is not bing back fed, it is important to + * note the all signals in the net list of the parts/bus. + * + * I.E. Not OFFIng PC1 on V3 would leave that pin back feeding the HMC part. As would not + * OFFIng PE4, not associated with SPI1 on V2, but would back feed an MPUxxxx on V3 + * + */ + +/* + * + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv3 Cube: FmuV2 PixhawkMini + * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1 No SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 EXTERN_DRDY SPI1:GYRO_DRDY NC + * PB1 MAG_DRDY nEXTERN_CS -SPI1:MAG_DRDY NC + * PB4 NC SPI1:ACCEL_DRDY NC + * PC1 SPI_INT_MAG_!CS -ADC1_IN11 NC + * PC2 nMPU_CS @MPU6000 @MPU9250 + * PC13 nGYRO_EXT_CS SPI1:nGYRO_CS NC + * PC14 nBARO_EXT_CS GPIO_EXT_1 -20608_DRDY + * PC15 nACCEL_MAG_EXT_CS SPI1:nACCEL_MAG_CS 20608_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000 @MPU9250 + * PE2 SPI_EXT_SCK NC + * PE4 MPU_EXT_CS SPI4:nSPI_EXT_NSS NC + * PE5 SPI_EXT_MISO NC + * PE6 SPI_EXT_MOSI NC + * + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + */ + +/*----------------------------------------------------------*/ +/* + * --------------- SPI1 -------------------- SPI4 -------------- Incompatibilities --------- + * FMUv2 Pixhawk Mini FmuV2 FmuV3 Cube + * Power Domain: VDD_3V3_SENSORS_EN NA V3V:SPI V5:SPI4 V3V:SPI1&SPI4 + * PA5 SPI_INT_SCK + * PA6 SPI_INT_MISO + * PA7 SPI_INT_MOSI + * PB0 NC SPI1:GYRO_DRDY SPI4:EXTERN_DRDY + * PB1 NC -SPI1:MAG_DRDY +SPI4:nEXTERN_CS + * PB4 NC SPI1:ACCEL_DRDY NC + * PC1 Spare ADC ( NC ) +SPI1:SPI_INT_MAG_!CS + * PC2 nMPU_CS @MPU6000 @MPU6000|MPU9250 + * PC13 NC SPI1:nGYRO_CS SPI4:nGYRO_EXT_CS + * PC14 20608_DRDY +GPIO_EXT_1 nBARO_EXT_CS + * PC15 20608_CS nACCEL_MAG_CS SPI4:nACCEL_MAG_EXT_CS + * PD7 nBARO_CS + * PD15 nMPU_DRDY @MPU6000 @MPU6000|MPU9250 + * PE2 NC SPI_EXT_SCK SPI_EXT_SCK + * PE4 NC SPI4:nSPI_EXT_NSS SPI4:nMPU_EXT_CS + * PE5 NC SPI_EXT_MISO SPI_EXT_MISO + * PE6 NC SPI_EXT_MOSI SPI_EXT_MOSI + * + * Notes: Prefixed with @ Does not effect board control + * Prefixed with + Input used as Output + * Prefixed with - Output used as Input + * Prefixed with SPIn: Bus changed + * + */ + constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { initSPIHWVersion(HW_VER_FMUV2, { initSPIBus(SPI::Bus::SPI1, { diff --git a/boards/px4/fmu-v4/src/board_config.h b/boards/px4/fmu-v4/src/board_config.h index 302b9381d3..a822097199 100644 --- a/boards/px4/fmu-v4/src/board_config.h +++ b/boards/px4/fmu-v4/src/board_config.h @@ -67,106 +67,9 @@ #define BOARD_ARMED_LED LED_BLUE #define BOARD_ARMED_STATE_LED LED_GREEN -/** - * Define the Chip Selects for SPI1 - * CS Devices DRDY - * ---- ----------------------------------------------- ----- - * PC2 MPU9250 PD15 - * PC15 ICM, ICM_20602, ICM_20608 PC14 - * PE15 HMC5983 PE12 - * ---- ----------------------------------------------- ----- - */ -#define GPIO_SPI1_CS_PORTC_PIN2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) -#define GPIO_SPI1_CS_PORTC_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) -#define GPIO_SPI1_CS_PORTE_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15) - -/* Define the Data Ready interrupts On SPI 1. */ -#define GPIO_DRDY_PORTD_PIN15 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_DRDY_PORTC_PIN14 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) -#define GPIO_DRDY_PORTE_PIN12 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12) - - -/* Define the Chip Selects for SPI2. */ -#define GPIO_SPI2_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI2_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) - -/* Define the Chip Selects for SPI4. */ - #ifdef CONFIG_STM32_SPI4 # define BOARD_HAS_BUS_MANIFEST 1 // We support a bus manifest because spi 4 is optional -# define GPIO_SPI4_CS_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8) //ESP_RTS_PIN #endif /* CONFIG_STM32_SPI4 */ -/** - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs. - */ -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - -/* SPI 1 bus off. */ -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -/* SPI 1 CS's off. */ -#define GPIO_SPI1_CS_OFF_PORTC_PIN2 _PIN_OFF(GPIO_SPI1_CS_PORTC_PIN2) -#define GPIO_SPI1_CS_OFF_PORTC_PIN15 _PIN_OFF(GPIO_SPI1_CS_PORTC_PIN15) -#define GPIO_SPI1_CS_OFF_PORTE_PIN15 _PIN_OFF(GPIO_SPI1_CS_PORTE_PIN15) - -/* SPI 1 DRDY's off. */ -#define GPIO_DRDY_OFF_PORTD_PIN15 _PIN_OFF(GPIO_DRDY_PORTD_PIN15) -#define GPIO_DRDY_OFF_PORTC_PIN14 _PIN_OFF(GPIO_DRDY_PORTC_PIN14) -#define GPIO_DRDY_OFF_PORTE_PIN12 _PIN_OFF(GPIO_DRDY_PORTE_PIN12) - -/* SPI 4 bus off. */ -#ifdef CONFIG_STM32_SPI4 -# define GPIO_SPI4_SCK_OFF _PIN_OFF(GPIO_SPI4_SCK) -# define GPIO_SPI4_MISO_OFF _PIN_OFF(GPIO_SPI4_MISO) -# define GPIO_SPI4_MOSI_OFF _PIN_OFF(GPIO_SPI4_MOSI) -#endif /* CONFIG_STM32_SPI4 */ - -/** - * N.B we do not have control over the SPI 2 buss powered devices - * so the the ms5611 is not resetable. - * - */ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON - -#ifdef CONFIG_STM32_SPI4 -# define PX4_SPI_BUS_EXTERNAL 4 -/* The mask passes to init the SPI bus pins - * N.B This works ONLY with buss numbers that are powers of 2 - * Adding SPI3 would break this! - */ -# define SPI_BUS_INIT_MASK_EXT PX4_SPI_BUS_EXTERNAL -#endif /* CONFIG_STM32_SPI4 */ - -#include - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_HMC5883) -#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_LIS3MDL) -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) - -/** - * Onboard MS5611 and FRAM are both on bus SPI2. - * spi_dev_e:SPIDEV_FLASH has the value 2 and is used in the NuttX ramtron driver. - * PX4_MK_SPI_SEL differentiate by adding in PX4_SPI_DEVICE_ID. - */ -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) - -#ifdef CONFIG_STM32_SPI4 -# define PX4_SPIDEV_EXTERNAL PX4_MK_SPI_SEL(0, 0) -#endif /* CONFIG_STM32_SPI4 */ - -/* I2C busses. */ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION /** * ADC channels: diff --git a/boards/px4/fmu-v4/src/init.c b/boards/px4/fmu-v4/src/init.c index 6c43b273ea..ec736005a1 100644 --- a/boards/px4/fmu-v4/src/init.c +++ b/boards/px4/fmu-v4/src/init.c @@ -306,12 +306,10 @@ __EXPORT int board_app_initialize(uintptr_t arg) } - // Default SPI1 to 1MHz and de-assert the known chip selects. + // Default SPI1 to 1MHz SPI_SETFREQUENCY(spi1, 10000000); SPI_SETBITS(spi1, 8); SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, PX4_SPIDEV_HMC, false); - SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); up_udelay(20); // Get the SPI port for the FRAM. @@ -332,8 +330,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000); SPI_SETBITS(spi2, 8); SPI_SETMODE(spi2, SPIDEV_MODE3); - SPI_SELECT(spi2, SPIDEV_FLASH(0), false); - SPI_SELECT(spi2, PX4_SPIDEV_BARO, false); #if defined(CONFIG_STM32_SPI4) @@ -347,11 +343,10 @@ __EXPORT int board_app_initialize(uintptr_t arg) syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n"); } else { - // Default SPI4 to 20 MHz and de-assert the known chip selects. + // Default SPI4 to 20 MHz SPI_SETFREQUENCY(spi4, 20 * 1000 * 1000); SPI_SETBITS(spi4, 8); SPI_SETMODE(spi4, SPIDEV_MODE3); - SPI_SELECT(spi4, PX4_SPIDEV_EXTERNAL, false); } } diff --git a/boards/px4/fmu-v4pro/src/board_config.h b/boards/px4/fmu-v4pro/src/board_config.h index 93d2796b20..c759fb714f 100644 --- a/boards/px4/fmu-v4pro/src/board_config.h +++ b/boards/px4/fmu-v4pro/src/board_config.h @@ -92,95 +92,9 @@ #define BOARD_ARMED_LED LED_BLUE #define BOARD_ARMED_STATE_LED LED_GREEN -/* Define the Chip Selects */ - -/* SPI Bus 1 Internal Sensors */ - -#define GPIO_SPI_CS_MPU9250 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) -#define GPIO_SPI_CS_LIS3MDL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15) -#define GPIO_SPI_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI_CS_ICM_2060X (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) +/* SPI */ #define GPIO_SPI_CS_TEMPCAL_EEPROM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) -/* SPI Bus 2 Memory */ - -#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) - -/* Aux Chip selects (not pined out on RC0 HW) */ - -#define GPIO_AUX_CS0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) -#define GPIO_AUX_CS1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN11) -#define GPIO_AUX_CS2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12) -#define GPIO_AUX_CS3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN13) -#define GPIO_AUX_CS4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN14) -#define GPIO_AUX_CS5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN15) - - -/* External Chip selects on Connectors ahead PAD3 */ - -#define GPIO_SPI5_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN6) -#define GPIO_SPI6_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN11) - -/* Define the Ready interrupts */ - -#define GPIO_DRDY_MPU9250 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_DRDY_LIS3MDL (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12) -#define GPIO_DRDY_ICM_2060X (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) - - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - -#define GPIO_SPI_CS_OFF_MPU9250 _PIN_OFF(GPIO_SPI_CS_MPU9250) -#define GPIO_SPI_CS_OFF_LIS3MDL _PIN_OFF(GPIO_SPI_CS_LIS3MDL) -#define GPIO_SPI_CS_OFF_MS5611 _PIN_OFF(GPIO_SPI_CS_MS5611) -#define GPIO_SPI_CS_OFF_ICM_2060X _PIN_OFF(GPIO_SPI_CS_ICM_2060X) -#define GPIO_SPI_CS_OFF_TEMPCAL_EEPROM _PIN_OFF(GPIO_SPI_CS_OFF_TEMPCAL_EEPROM) - -#define GPIO_DRDY_OFF_MPU9250 _PIN_OFF(GPIO_DRDY_MPU9250) -#define GPIO_DRDY_OFF_LIS3MDL _PIN_OFF(GPIO_DRDY_LIS3MDL) -#define GPIO_DRDY_OFF_ICM_2060X _PIN_OFF(GPIO_DRDY_ICM_2060X) - - -/* SPI1 off */ - -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS -#define PX4_SPI_BUS_EXT0 5 -#define PX4_SPI_BUS_EXT1 6 - -#define PX4_SPI_BUS_EXT PX4_SPI_BUS_EXT0 - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ - -#include -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) -#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_HMC5883) -#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_LIS3MDL) -#define PX4_SPIDEV_EEPROM PX4_MK_SPI_SEL(0, DRV_DEVTYPE_UNUSED) -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) - -#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(0, 0) -#define PX4_SPIDEV_EXT1 PX4_MK_SPI_SEL(0, 1) - -#define PX4_SPIDEV_RM_EXT PX4_SPIDEV_EXT0 - -/* I2C busses */ -#define PX4_I2C_BUS_ONBOARD 1 -#define PX4_I2C_BUS_EXPANSION 2 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD - /* * ADC channels * diff --git a/boards/px4/fmu-v4pro/src/init.c b/boards/px4/fmu-v4pro/src/init.c index efdf175b72..6beb2497d9 100644 --- a/boards/px4/fmu-v4pro/src/init.c +++ b/boards/px4/fmu-v4pro/src/init.c @@ -328,11 +328,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi1, 10000000); SPI_SETBITS(spi1, 8); SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, PX4_SPIDEV_ICM_20602, false); - SPI_SELECT(spi1, PX4_SPIDEV_BARO, false); - SPI_SELECT(spi1, PX4_SPIDEV_LIS, false); - SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); - SPI_SELECT(spi1, PX4_SPIDEV_EEPROM, false); up_udelay(20); /* Get the SPI port for the FRAM */ @@ -352,7 +347,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000); SPI_SETBITS(spi2, 8); SPI_SETMODE(spi2, SPIDEV_MODE3); - SPI_SELECT(spi2, SPIDEV_FLASH(0), false); /* Configure SPI 5-based devices */ @@ -368,7 +362,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi5, 10000000); SPI_SETBITS(spi5, 8); SPI_SETMODE(spi5, SPIDEV_MODE3); - SPI_SELECT(spi5, PX4_SPIDEV_EXT0, false); /* Configure SPI 6-based devices */ @@ -384,7 +377,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi6, 10000000); SPI_SETBITS(spi6, 8); SPI_SETMODE(spi6, SPIDEV_MODE3); - SPI_SELECT(spi6, PX4_SPIDEV_EXT1, false); #ifdef CONFIG_MMCSD /* First, get an instance of the SDIO interface */ diff --git a/boards/px4/fmu-v5/src/board_config.h b/boards/px4/fmu-v5/src/board_config.h index bfa0ccd6a5..f2509946a5 100644 --- a/boards/px4/fmu-v5/src/board_config.h +++ b/boards/px4/fmu-v5/src/board_config.h @@ -96,130 +96,6 @@ #define BOARD_OVERLOAD_LED LED_RED #define BOARD_ARMED_STATE_LED LED_BLUE -/* SENSORS are on SPI1, 5, 6 - * MEMORY is on bus SPI2 - * MS5611 is on bus SPI4 - */ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_MEMORY 2 -#define PX4_SPI_BUS_BARO 4 -#define PX4_SPI_BUS_EXTERNAL1 5 -#define PX4_SPI_BUS_EXTERNAL2 6 - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ - -#define GPIO_SPI1_CS1_ICM20689 /* PF2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN2) -#define GPIO_SPI1_CS2_ICM20602 /* PF3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN3) -#define GPIO_SPI1_CS3_BMI055_GYRO /* PF4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN4) -#define GPIO_SPI1_CS4_BMI055_ACC /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) -#define GPIO_SPI1_CS5_AUX_MEM /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) - - -/* Define the SPI1 Data Ready interrupts */ - -#define GPIO_SPI1_DRDY1_ICM20689 /* PB4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4) -#define GPIO_SPI1_DRDY2_BMI055_GYRO /* PB14 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14) -#define GPIO_SPI1_DRDY3_BMI055_ACC /* PB15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN15) -#define GPIO_SPI1_DRDY4_ICM20602 /* PC5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN5) -#define GPIO_SPI1_DRDY5_BMI055_GYRO /* PC13 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13) -#define GPIO_SPI1_DRDY6_BMI055_ACC /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN10) - -/* SPI1 off */ - -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20689) -#define GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO _PIN_OFF(GPIO_SPI1_DRDY2_BMI055_GYRO) -#define GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC _PIN_OFF(GPIO_SPI1_DRDY3_BMI055_ACC) -#define GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY4_ICM20602) -#define GPIO_DRDY_OFF_SPI1_DRDY5_BMI055_GYRO _PIN_OFF(GPIO_SPI1_DRDY5_BMI055_GYRO) -#define GPIO_DRDY_OFF_SPI1_DRDY6_BMI055_ACC _PIN_OFF(GPIO_SPI1_DRDY6_BMI055_ACC) - -/* SPI 2 CS */ - -#define GPIO_SPI2_CS_FRAM /* PF5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN5) - -/* SPI 4 CS */ - -#define GPIO_SPI4_CS1_MS5611 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10) -#define GPIO_SPI4_CS2 /* PF11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN11) - -/* SPI 5 CS */ - -#define SPI5_CS1_EXTERNAL1 /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN4) -#define SPI5_CS2_EXTERNAL1 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) -#define SPI5_CS3_EXTERNAL1 /* PI11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN11) - -/* Define the SPI1 Data Ready and Control signals */ - -#define GPIO_SPI5_DRDY7_EXTERNAL1 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_nSPI5_RESET_EXTERNAL1 /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) -#define GPIO_SPI5_SYNC_EXTERNAL1 /* PH15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|PORTH|PIN15) - -/* SPI 6 */ - -#define SPI6_CS1_EXTERNAL2 /* PI6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN6) -#define SPI6_CS2_EXTERNAL2 /* PI7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN7) -#define SPI6_CS3_EXTERNAL2 /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN8) - - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - - -#define GPIO_DRDY_OFF_SPI5_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI5_DRDY7_EXTERNAL1) - - -/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */ -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY -/* ^ END Legacy SPI defines TODO: fix this with enumeration */ -#include - -#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20689) -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI055) -#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI055) -#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(0,4) -#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS2_ICM20602, GPIO_SPI1_CS3_BMI055_GYRO, GPIO_SPI1_CS4_BMI055_ACC, GPIO_SPI1_CS5_AUX_MEM} - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI2_CS_FRAM} - -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0,DRV_BARO_DEVTYPE_MS5611) -#define PX4_SPIDEV_SPI4_CS2 PX4_MK_SPI_SEL(PX4_SPI_BUS_BARO,1) -#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI4_CS1_MS5611, GPIO_SPI4_CS2} - -#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,0) -#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,1) -#define PX4_SPIDEV_EXTERNAL1_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,2) -#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI5_CS1_EXTERNAL1, SPI5_CS2_EXTERNAL1, SPI5_CS3_EXTERNAL1} - -#define PX4_SPIDEV_EXTERNAL2_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,0) -#define PX4_SPIDEV_EXTERNAL2_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,1) -#define PX4_SPIDEV_EXTERNAL2_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,2) -#define PX4_EXTERNAL2_BUS_CS_GPIO {SPI6_CS1_EXTERNAL2, SPI6_CS2_EXTERNAL2, SPI6_CS3_EXTERNAL2} - - -/* I2C busses */ - -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_ONBOARD 3 -#define PX4_I2C_BUS_EXPANSION2 4 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - -#define BOARD_NUMBER_I2C_BUSES 4 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} - /* * ADC channels * diff --git a/boards/px4/fmu-v5x/src/board_config.h b/boards/px4/fmu-v5x/src/board_config.h index 5814fd3841..0ff69f6d28 100644 --- a/boards/px4/fmu-v5x/src/board_config.h +++ b/boards/px4/fmu-v5x/src/board_config.h @@ -100,169 +100,19 @@ # define BOARD_ARMED_STATE_LED LED_BLUE #endif -/* SPI - * - * SPI1 is sensors1 - * ICM-20602 - * CS PI9 - * DRDY PF2 - * - * SPI2 is sensors2 - * ISM330 - * CS PH5 - * DRDY PH12 - * - * SPI3 is sensors3 - * BMI088 - * CS ACCL PI4 - * CS GYRO PI8 - * DRDY ACCL PI6 - * DRDY GYRO PI7 - * - * SPI5 is FRAM - * FM25V02A - * CS PG7 - * - * SPI6 is EXTERNAL1 - * - * CS1 PI10 - * CS2 PA15 - * DRDY1 PD11 - * DRDY2 PD12 - * - */ +/* SPI */ -#define PX4_SPI_BUS_SENSORS1 1 -#define PX4_SPI_BUS_SENSORS2 2 -#define PX4_SPI_BUS_SENSORS3 3 -#define PX4_SPI_BUS_SENSORS4 4 - -#define PX4_SPI_BUS_MAG PX4_SPI_BUS_SENSORS4 -#define PX4_SPI_BUS_MEMORY 5 -#define PX4_SPI_BUS_EXTERNAL1 6 - -/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ - -/* SPI 1 CS */ - -#define GPIO_SPI1_nCS1_ICM20602 /* PI9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN9) - -/* Define the SPI1 Data Ready interrupts */ - -#define GPIO_SPI1_DRDY1_ICM20602 /* PF2 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTF|GPIO_PIN2) - -/* SPI1 off */ - -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20602) - -/* SPI 2 CS */ - -#define GPIO_SPI2_nCS1_ISM330 /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5) - -/* Define the SPI2 Data Ready interrupts */ - -#define GPIO_SPI2_DRDY1_ISM330 /* PH12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTH|GPIO_PIN12) - -/* SPI2 off */ - -#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK) -#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO) -#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI) - -#define GPIO_DRDY_OFF_SPI2_DRDY1_ISM330 _PIN_OFF(GPIO_SPI2_DRDY1_ISM330) - -/* SPI 3 CS */ - -#define GPIO_SPI3_nCS1_BMI088_ACCEL /* PI4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN4) -#define GPIO_SPI3_nCS2_BMI088_GYRO /* PI8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN8) - -/* Define the SPI3 Data Ready interrupts */ +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) #define GPIO_SYNC /* PH10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) -#define GPIO_SPI3_DRDY1_BMI088_INT1_ACCEL /* PI6 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN6) -#define GPIO_SPI3_DRDY2_BMI088_INT3_GYRO /* PI7 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTI|GPIO_PIN7) - -/* SPI3 off */ - -#define GPIO_SPI3_SCK_OFF _PIN_OFF(GPIO_SPI3_SCK) -#define GPIO_SPI3_MISO_OFF _PIN_OFF(GPIO_SPI3_MISO) -#define GPIO_SPI3_MOSI_OFF _PIN_OFF(GPIO_SPI3_MOSI) - -#define GPIO_DRDY_OFF_SPI3_DRDY1_BMI088 _PIN_OFF(GPIO_SPI3_DRDY1_BMI088_INT1_ACCEL) -#define GPIO_DRDY_OFF_SPI3_DRDY2_BMI088 _PIN_OFF(GPIO_SPI3_DRDY2_BMI088_INT3_GYRO) - -/* SPI 5 CS */ - -#define GPIO_SPI5_nCS1_FRAM /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN7) - -/* SPI 6 */ - -#define GPIO_SPI6_nCS1_EXTERNAL1 /* PI10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10) -#define GPIO_SPI6_nCS2_EXTERNAL1 /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15) - -/* Define the SPI6 Data Ready interrupts */ - -#define GPIO_SPI6_DRDY1_EXTERNAL1 /* PD11 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN11) -#define GPIO_SPI6_DRDY2_EXTERNAL1 /* PD12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN12) -#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) - -/* SPI6 off */ - -#define GPIO_SPI6_SCK_OFF _PIN_OFF(GPIO_SPI6_SCK) -#define GPIO_SPI6_MISO_OFF _PIN_OFF(GPIO_SPI6_MISO) -#define GPIO_SPI6_MOSI_OFF _PIN_OFF(GPIO_SPI6_MOSI) - -#define GPIO_DRDY_OFF_SPI6_DRDY1 _PIN_OFF(GPIO_SPI6_DRDY1_EXTERNAL1) -#define GPIO_DRDY_OFF_SPI6_DRDY2 _PIN_OFF(GPIO_SPI6_DRDY2_EXTERNAL1) - -/* - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs - */ - -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) -#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY - -#include -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SENSORS1_BUS_CS_GPIO {GPIO_SPI1_nCS1_ICM20602} - -#define PX4_SPIDEV_ISM330 PX4_MK_SPI_SEL(0,DRV_IMU_DEVTYPE_ST_ISM330DLC) -#define PX4_SENSORS2_BUS_CS_GPIO {GPIO_SPI2_nCS1_ISM330} - -#define PX4_SPIDEV_BMI088_GYR PX4_MK_SPI_SEL(0,DRV_GYR_DEVTYPE_BMI088) -#define PX4_SPIDEV_BMI088_ACC PX4_MK_SPI_SEL(0,DRV_ACC_DEVTYPE_BMI088) -#define PX4_SENSORS3_BUS_CS_GPIO {GPIO_SPI3_nCS2_BMI088_GYRO, GPIO_SPI3_nCS1_BMI088_ACCEL} - -#define PX4_SPIDEV_MEMORY SPIDEV_FLASH(0) -#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI5_nCS1_FRAM} - -#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(0,0) -#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(0,1) -#define PX4_EXTERNAL1_BUS_CS_GPIO {GPIO_SPI6_nCS1_EXTERNAL1, GPIO_SPI6_nCS2_EXTERNAL1} - - /* I2C busses */ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_EXPANSION1 2 -#define PX4_I2C_BUS_EXPANSION2 3 -#define PX4_I2C_BUS_ONBOARD 4 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION - /* Devices on the onboard buses. * * Note that these are unshifted addresses. */ #define PX4_I2C_OBDEV_A71CH 0x49 -#define BOARD_NUMBER_I2C_BUSES 4 -#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} - #define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) #define GPIO_SE050_nRST /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6) diff --git a/boards/px4/raspberrypi/src/board_config.h b/boards/px4/raspberrypi/src/board_config.h index 3cc4658b21..9414f7e306 100644 --- a/boards/px4/raspberrypi/src/board_config.h +++ b/boards/px4/raspberrypi/src/board_config.h @@ -48,15 +48,8 @@ /* * I2C busses */ -#define PX4_I2C_BUS_ONBOARD 1 -#define PX4_I2C_BUS_EXPANSION 0 - #define PX4_NUMBER_I2C_BUSES 2 -// SPI -#define PX4_SPI_BUS_SENSORS 0 -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, 0) // spidev0.0 - #define ADC_BATTERY_VOLTAGE_CHANNEL 0 #define ADC_BATTERY_CURRENT_CHANNEL -1 #define ADC_AIRSPEED_VOLTAGE_CHANNEL 2 diff --git a/boards/px4/sitl/src/board_config.h b/boards/px4/sitl/src/board_config.h index ee2a2c066a..b0f8995ba0 100644 --- a/boards/px4/sitl/src/board_config.h +++ b/boards/px4/sitl/src/board_config.h @@ -47,8 +47,6 @@ #define BOARD_HAS_POWER_CONTROL #define BOARD_HAS_NO_BOOTLOADER -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_ONBOARD 2 #define PX4_NUMBER_I2C_BUSES 1 #define BOARD_NUMBER_BRICKS 0 diff --git a/boards/uvify/core/src/board_config.h b/boards/uvify/core/src/board_config.h index 3ee3c98156..de1b4730c5 100644 --- a/boards/uvify/core/src/board_config.h +++ b/boards/uvify/core/src/board_config.h @@ -67,108 +67,9 @@ #define BOARD_ARMED_LED LED_BLUE #define BOARD_ARMED_STATE_LED LED_GREEN -/** - * The MPU9250 is default. The wrong driver will fail during start because of an incorrect WHO_AM_I register. - */ -#define GPIO_SPI1_CS_PORTC_PIN2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) - -/** - * The ICM20608G is default. The wrong driver will fail during start because of an incorrect WHO_AM_I register. - */ -#define GPIO_SPI1_CS_PORTC_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) - -/** - * Reserved. The wrong driver will fail during start because of an incorrect WHO_AM_I register. - */ -#define GPIO_SPI1_CS_PORTE_PIN15 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15) - -/* Define the Data Ready interrupts On SPI 1. */ -#define GPIO_DRDY_PORTD_PIN15 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15) -#define GPIO_DRDY_PORTC_PIN14 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14) -#define GPIO_DRDY_PORTE_PIN12 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12) - - -/* Define the Chip Selects for SPI2. */ -#define GPIO_SPI2_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) -#define GPIO_SPI2_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) - -/* Define the Chip Selects for SPI4. */ - #ifdef CONFIG_STM32_SPI4 # define BOARD_HAS_BUS_MANIFEST 1 // We support a bus manifest because spi 4 is optional -# define GPIO_SPI4_CS_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8) //ESP_RTS_PIN #endif /* CONFIG_STM32_SPI4 */ -/** - * Define the ability to shut off off the sensor signals - * by changing the signals to inputs. - */ -#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) - -/* SPI 1 bus off. */ -#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK) -#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO) -#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI) - -/* SPI 1 CS's off. */ -#define GPIO_SPI1_CS_OFF_PORTC_PIN2 _PIN_OFF(GPIO_SPI1_CS_PORTC_PIN2) -#define GPIO_SPI1_CS_OFF_PORTC_PIN15 _PIN_OFF(GPIO_SPI1_CS_PORTC_PIN15) -#define GPIO_SPI1_CS_OFF_PORTE_PIN15 _PIN_OFF(GPIO_SPI1_CS_PORTE_PIN15) - -/* SPI 1 DRDY's off. */ -#define GPIO_DRDY_OFF_PORTD_PIN15 _PIN_OFF(GPIO_DRDY_PORTD_PIN15) -#define GPIO_DRDY_OFF_PORTC_PIN14 _PIN_OFF(GPIO_DRDY_PORTC_PIN14) -#define GPIO_DRDY_OFF_PORTE_PIN12 _PIN_OFF(GPIO_DRDY_PORTE_PIN12) - -/* SPI 4 bus off. */ -#ifdef CONFIG_STM32_SPI4 -# define GPIO_SPI4_SCK_OFF _PIN_OFF(GPIO_SPI4_SCK) -# define GPIO_SPI4_MISO_OFF _PIN_OFF(GPIO_SPI4_MISO) -# define GPIO_SPI4_MOSI_OFF _PIN_OFF(GPIO_SPI4_MOSI) -#endif /* CONFIG_STM32_SPI4 */ - -/** - * N.B we do not have control over the SPI 2 buss powered devices - * so the the ms5611 is not resetable. - * - */ - -#define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_RAMTRON 2 -#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON - -#ifdef CONFIG_STM32_SPI4 -# define PX4_SPI_BUS_EXTERNAL 4 -/* The mask passes to init the SPI bus pins - * N.B This works ONLY with buss numbers that are powers of 2 - * Adding SPI3 would break this! - */ -# define SPI_BUS_INIT_MASK_EXT PX4_SPI_BUS_EXTERNAL -#endif /* CONFIG_STM32_SPI4 */ - -#include - -/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */ -#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU6000) -#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_HMC5883) -#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(0, DRV_MAG_DEVTYPE_LIS3MDL) -#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20608) -#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_ICM20602) -#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(0, DRV_IMU_DEVTYPE_MPU9250) - -/** - * Onboard MS5611 and FRAM are both on bus SPI2. - * spi_dev_e:SPIDEV_FLASH has the value 2 and is used in the NuttX ramtron driver. - * PX4_MK_SPI_SEL differentiate by adding in PX4_SPI_DEVICE_ID. - */ -#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(0, DRV_BARO_DEVTYPE_MS5611) - -#ifdef CONFIG_STM32_SPI4 -# define PX4_SPIDEV_EXTERNAL PX4_MK_SPI_SEL(0, 0) -#endif /* CONFIG_STM32_SPI4 */ - -/* I2C busses. */ -#define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION /** * ADC channels: diff --git a/boards/uvify/core/src/init.c b/boards/uvify/core/src/init.c index 04ae1f60a5..e4c6ca166e 100644 --- a/boards/uvify/core/src/init.c +++ b/boards/uvify/core/src/init.c @@ -310,8 +310,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi1, 10000000); SPI_SETBITS(spi1, 8); SPI_SETMODE(spi1, SPIDEV_MODE3); - SPI_SELECT(spi1, PX4_SPIDEV_HMC, false); - SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); up_udelay(20); // Get the SPI port for the FRAM. @@ -332,8 +330,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000); SPI_SETBITS(spi2, 8); SPI_SETMODE(spi2, SPIDEV_MODE3); - SPI_SELECT(spi2, SPIDEV_FLASH(0), false); - SPI_SELECT(spi2, PX4_SPIDEV_BARO, false); #if defined(CONFIG_STM32_SPI4) @@ -351,7 +347,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) SPI_SETFREQUENCY(spi4, 20 * 1000 * 1000); SPI_SETBITS(spi4, 8); SPI_SETMODE(spi4, SPIDEV_MODE3); - SPI_SELECT(spi4, PX4_SPIDEV_EXTERNAL, false); } }