Skip to content

Commit

Permalink
boards name and number external SPI consistently
Browse files Browse the repository at this point in the history
  • Loading branch information
dagar committed Jan 29, 2019
1 parent d02685c commit b582f08
Show file tree
Hide file tree
Showing 37 changed files with 121 additions and 145 deletions.
4 changes: 2 additions & 2 deletions boards/airmind/mindpx-v2/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@

#define PX4_SPI_BUS_SENSORS 4
#define PX4_SPI_BUS_RAMTRON 1
#define PX4_SPI_BUS_EXT 2
#define PX4_SPI_BUS_EXTERNAL1 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 */
Expand All @@ -124,7 +124,7 @@
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)

/* External bus */
#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 1)
#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1)


/* I2C busses */
Expand Down
2 changes: 1 addition & 1 deletion boards/airmind/mindpx-v2/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SETFREQUENCY(spi2, 10000000);
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);
SPI_SELECT(spi2, PX4_SPIDEV_EXT0, false);
SPI_SELECT(spi2, PX4_SPIDEV_EXTERNAL1_1, false);


#ifdef CONFIG_MMCSD
Expand Down
13 changes: 5 additions & 8 deletions boards/bitcraze/crazyflie/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,22 +111,19 @@
/* SPI Busses */

/* SPI1 Bus */
#define PX4_SPI_BUS_EXPANSION 1
#define PX4_SPI_BUS_EXTERNAL1 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 }
#define PX4_SPI_BUS_EXTERNAL1_CS_GPIO { GPIO_SPI1_CS0_EXT, GPIO_SPI1_CS1_EXT, GPIO_SPI1_CS2_EXT }

/* SPI1 Devices */
#define PX4_SPIDEV_EXPANSION_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXPANSION, 0) // SD CARD BREAKOUT
#define PX4_SPIDEV_EXPANSION_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXPANSION, 1) // OPTICAL FLOW BREAKOUT
#define PX4_SPIDEV_EXPANSION_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXPANSION, 2)

#define PX4_FLOW_BUS_FIRST_CS PX4_SPIDEV_EXPANSION_1
#define PX4_FLOW_BUS_LAST_CS PX4_SPIDEV_EXPANSION_3
#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 0) // SD CARD BREAKOUT
#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1) // OPTICAL FLOW BREAKOUT
#define PX4_SPIDEV_EXTERNAL1_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 2)

/* SPI1 off */
#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK)
Expand Down
6 changes: 3 additions & 3 deletions boards/bitcraze/crazyflie/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
/* Debug ********************************************************************/

/* Define CS GPIO array */
static const uint32_t spi1selects_gpio[] = PX4_FLOW_BUS_CS_GPIO;
static const uint32_t spi1selects_gpio[] = PX4_SPI_BUS_EXTERNAL1_CS_GPIO;


/************************************************************************************
Expand Down Expand Up @@ -66,10 +66,10 @@ __EXPORT int stm32_spi_bus_initialize(void)
/* Configure SPI-based devices */

/* Get the external SPI port */
spi_expansion = stm32_spibus_initialize(PX4_SPI_BUS_EXPANSION);
spi_expansion = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);

if (!spi_expansion) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXPANSION);
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
return -ENODEV;
}

Expand Down
2 changes: 1 addition & 1 deletion boards/gumstix/aerocore2/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@

#define PX4_SPI_BUS_SENSORS 3
#define PX4_SPI_BUS_RAMTRON 4
#define PX4_SPI_BUS_EXT 1
#define PX4_SPI_BUS_EXTERNAL1 1
#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 SPI3 */
Expand Down
23 changes: 11 additions & 12 deletions boards/nxp/fmuk66-v3/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -201,9 +201,8 @@ __BEGIN_DECLS

#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_EXTERNAL1 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 */
Expand Down Expand Up @@ -244,17 +243,17 @@ __BEGIN_DECLS
#define PX4_SENSOR_BUS_FIRST_CS PX4_SPIDEV_ACCEL_MAG
#define PX4_SENSOR_BUS_LAST_CS PX4_SPIDEV_GYRO

#define PX4_SPIDEV_EXTERNAL1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL,0)
#define PX4_SPIDEV_EXTERNAL2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL,1)
#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_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
#define PX4_EXTERNAL_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL1_1
#define PX4_EXTERNAL_BUS_LAST_CS PX4_SPIDEV_EXTERNAL1_2

#define PX4_SPIDEV_ICM_20602 PX4_SPIDEV_EXTERNAL1_1
#define PX4_SPIDEV_ICM_20608 PX4_SPIDEV_EXTERNAL1_1
#define PX4_SPIDEV_ICM_20689 PX4_SPIDEV_EXTERNAL1_1
#define PX4_SPIDEV_EXT_MPU PX4_SPIDEV_EXTERNAL1_1
#define PX4_SPIDEV_MPU PX4_SPIDEV_EXTERNAL1_1

/* I2C busses */

Expand Down
6 changes: 3 additions & 3 deletions boards/nxp/fmuk66-v3/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -229,10 +229,10 @@ __EXPORT int fmuk66_spi_bus_initialize(void)

/* Configure EXTERNAL SPI-based devices */

spi_ext = px4_spibus_initialize(PX4_SPI_BUS_EXTERNAL);
spi_ext = px4_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);

if (!spi_ext) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL);
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
return -ENODEV;
}

Expand Down Expand Up @@ -350,7 +350,7 @@ void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected
/* SPI select is active low, so write !selected to select the device */

int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_EXTERNAL);
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_EXTERNAL1);

/* Making sure the other peripherals are not selected */

Expand Down
12 changes: 6 additions & 6 deletions boards/px4/fmu-v2/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@

#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
#define PX4_SPI_BUS_EXT 4
#define PX4_SPI_BUS_EXTERNAL1 4
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS

/* Use these to select a specific SPI device on SPI1 */
Expand All @@ -215,11 +215,11 @@

/* FMUv3 SPI on external bus */

#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 1)
#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 2)
#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 3)
#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 4)
#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 5)
#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1)
#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 2)
#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 3)
#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 4)
#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 5)

/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v2/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -490,10 +490,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);

spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXT);
spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);

if (!spi4) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
led_on(LED_AMBER);
return -ENODEV;
}
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v2/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -452,7 +452,7 @@ __EXPORT bool px4_spi_bus_external(int bus)
return false;

} else {
if (bus == PX4_SPI_BUS_EXT) {
if (bus == PX4_SPI_BUS_EXTERNAL1) {
return true;
}
}
Expand Down
12 changes: 6 additions & 6 deletions boards/px4/fmu-v3/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@

#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_RAMTRON 2
#define PX4_SPI_BUS_EXT 4
#define PX4_SPI_BUS_EXTERNAL1 4
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS

/* Use these to select a specific SPI device on SPI1 */
Expand All @@ -215,11 +215,11 @@

/* FMUv3 SPI on external bus */

#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 1)
#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 2)
#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 3)
#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 4)
#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT, 5)
#define PX4_SPIDEV_EXT_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1)
#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 2)
#define PX4_SPIDEV_EXT_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 3)
#define PX4_SPIDEV_EXT_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 4)
#define PX4_SPIDEV_EXT_BMI PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 5)

/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v3/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -490,10 +490,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SETBITS(spi2, 8);
SPI_SETMODE(spi2, SPIDEV_MODE3);

spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXT);
spi4 = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);

if (!spi4) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT);
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
led_on(LED_AMBER);
return -ENODEV;
}
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v3/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -452,7 +452,7 @@ __EXPORT bool px4_spi_bus_external(int bus)
return false;

} else {
if (bus == PX4_SPI_BUS_EXT) {
if (bus == PX4_SPI_BUS_EXTERNAL1) {
return true;
}
}
Expand Down
6 changes: 3 additions & 3 deletions boards/px4/fmu-v4/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,12 +150,12 @@
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_RAMTRON

#ifdef CONFIG_STM32_SPI4
# define PX4_SPI_BUS_EXTERNAL 4
# define PX4_SPI_BUS_EXTERNAL1 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
# define SPI_BUS_INIT_MASK_EXT PX4_SPI_BUS_EXTERNAL1
#endif /* CONFIG_STM32_SPI4 */

#define SPI_BUS_INIT_MASK (PX4_SPI_BUS_RAMTRON | PX4_SPI_BUS_SENSORS)
Expand Down Expand Up @@ -183,7 +183,7 @@
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_BARO, 3)

#ifdef CONFIG_STM32_SPI4
# define PX4_SPIDEV_EXTERNAL PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL, 1)
# define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1)
#endif /* CONFIG_STM32_SPI4 */

/* I2C busses. */
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -366,7 +366,7 @@ __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);
SPI_SELECT(spi4, PX4_SPIDEV_EXTERNAL1_1, false);
}
}

Expand Down
8 changes: 4 additions & 4 deletions boards/px4/fmu-v4/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ __EXPORT bool board_has_bus(enum board_bus_types type, uint32_t bus)
switch (type) {
case BOARD_SPI_BUS:
#ifdef CONFIG_STM32_SPI4
rv = bus != PX4_SPI_BUS_EXTERNAL || (stm32_gpioread(GPIO_8266_GPIO2) == 0);
rv = bus != PX4_SPI_BUS_EXTERNAL1 || (stm32_gpioread(GPIO_8266_GPIO2) == 0);
#endif /* CONFIG_STM32_SPI4 */
break;

Expand Down Expand Up @@ -116,7 +116,7 @@ __EXPORT void stm32_spiinitialize(int mask)

#ifdef CONFIG_STM32_SPI4

if (mask & PX4_SPI_BUS_EXTERNAL) {
if (mask & PX4_SPI_BUS_EXTERNAL1) {
stm32_configgpio(GPIO_SPI4_CS_1); //add cs
}

Expand Down Expand Up @@ -207,7 +207,7 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
#ifdef CONFIG_STM32_SPI4
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
if (devid == PX4_SPIDEV_EXTERNAL && stm32_gpioread(GPIO_8266_GPIO2) == 0) {
if (devid == PX4_SPIDEV_EXTERNAL1_1 && stm32_gpioread(GPIO_8266_GPIO2) == 0) {
stm32_gpiowrite(GPIO_SPI4_CS_1, !selected); // add cs
}
}
Expand Down Expand Up @@ -310,7 +310,7 @@ __EXPORT void board_spi_reset(int ms)
#ifdef CONFIG_STM32_SPI4

if (stm32_gpioread(GPIO_8266_GPIO2) == 0) {
stm32_spiinitialize(PX4_SPI_BUS_EXTERNAL);
stm32_spiinitialize(PX4_SPI_BUS_EXTERNAL1);
stm32_configgpio(GPIO_SPI4_SCK);
stm32_configgpio(GPIO_SPI4_MISO);
stm32_configgpio(GPIO_SPI4_MOSI);
Expand Down
10 changes: 4 additions & 6 deletions boards/px4/fmu-v4pro/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,10 +155,8 @@
#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
#define PX4_SPI_BUS_EXTERNAL1 5
#define PX4_SPI_BUS_EXTERNAL2 6

/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */

Expand All @@ -175,8 +173,8 @@
#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 13)
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 14)

#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT0, 1)
#define PX4_SPIDEV_EXT1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXT1, 1)
#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1, 1)
#define PX4_SPIDEV_EXT1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2, 1)

#define PX4_SPIDEV_RM_EXT PX4_SPIDEV_EXT0

Expand Down
8 changes: 4 additions & 4 deletions boards/px4/fmu-v4pro/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -359,10 +359,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)

/* Configure SPI 5-based devices */

spi5 = stm32_spibus_initialize(PX4_SPI_BUS_EXT0);
spi5 = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);

if (!spi5) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT0);
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
led_on(LED_RED);
return -ENODEV;
}
Expand All @@ -375,10 +375,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)

/* Configure SPI 6-based devices */

spi6 = stm32_spibus_initialize(PX4_SPI_BUS_EXT1);
spi6 = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL2);

if (!spi6) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXT1);
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL2);
led_on(LED_RED);
return -ENODEV;
}
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/barometer/bmp280/bmp280.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -543,8 +543,8 @@ struct bmp280_bus_option {
bool external;
BMP280 *dev;
} bus_options[] = {
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT)
{ BMP280_BUS_SPI_EXTERNAL, "/dev/bmp280_spi_ext", &bmp280_spi_interface, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_BARO, true, NULL },
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXTERNAL1)
{ BMP280_BUS_SPI_EXTERNAL, "/dev/bmp280_spi_ext", &bmp280_spi_interface, PX4_SPI_BUS_EXTERNAL1, PX4_SPIDEV_EXT_BARO, true, NULL },
#endif
#if defined(PX4_SPIDEV_BARO)
# if defined(PX4_SPIDEV_BARO_BUS)
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/barometer/mpl3115a2/mpl3115a2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -658,8 +658,8 @@ struct mpl3115a2_bus_option {
uint8_t busnum;
MPL3115A2 *dev;
} bus_options[] = {
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT)
{ MPL3115A2_BUS_SPI_EXTERNAL, "/dev/mpl3115a2_spi_ext", &MPL3115A2_spi_interface, PX4_SPI_BUS_EXT, NULL },
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXTERNAL1)
{ MPL3115A2_BUS_SPI_EXTERNAL, "/dev/mpl3115a2_spi_ext", &MPL3115A2_spi_interface, PX4_SPI_BUS_EXTERNAL1, NULL },
#endif
#ifdef PX4_SPIDEV_BARO
{ MPL3115A2_BUS_SPI_INTERNAL, "/dev/mpl3115a2_spi_int", &MPL3115A2_spi_interface, PX4_SPI_BUS_BARO, NULL },
Expand Down
4 changes: 2 additions & 2 deletions src/drivers/barometer/ms5611/ms5611.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -813,8 +813,8 @@ struct ms5611_bus_option {
uint8_t busnum;
MS5611 *dev;
} bus_options[] = {
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT)
{ MS5611_BUS_SPI_EXTERNAL, "/dev/ms5611_spi_ext", &MS5611_spi_interface, PX4_SPI_BUS_EXT, NULL },
#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXTERNAL1)
{ MS5611_BUS_SPI_EXTERNAL, "/dev/ms5611_spi_ext", &MS5611_spi_interface, PX4_SPI_BUS_EXTERNAL1, NULL },
#endif
#ifdef PX4_SPIDEV_BARO
{ MS5611_BUS_SPI_INTERNAL, "/dev/ms5611_spi_int", &MS5611_spi_interface, PX4_SPI_BUS_BARO, NULL },
Expand Down
Loading

0 comments on commit b582f08

Please sign in to comment.