Skip to content

Commit

Permalink
boards: add new spi+i2c config
Browse files Browse the repository at this point in the history
Chip-select and SPI initialization uses the new config, whereas the drivers
still use the existing defines.

The configuration in board_config.h can be removed after all drivers are
updated.
  • Loading branch information
bkueng committed Feb 24, 2020
1 parent 61f7f74 commit 5a986ae
Show file tree
Hide file tree
Showing 134 changed files with 2,437 additions and 5,654 deletions.
3 changes: 2 additions & 1 deletion boards/aerotenna/ocpoc/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,5 +32,6 @@
############################################################################

add_library(drivers_board
empty.c
i2c.cpp
spi.cpp
)
7 changes: 4 additions & 3 deletions boards/aerotenna/ocpoc/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,11 @@
#define PX4_I2C_BUS_LED 1

// SPI
#include <drivers/drv_sensor.h>
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 0) // spidev1.0 - mpu9250
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1) // spidev1.1 - ms5611
//#define PX4_SPIDEV_MPU2 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2) // TODO: where is the 2nd mpu9250?
#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

Expand Down
Empty file removed boards/aerotenna/ocpoc/src/empty.c
Empty file.
42 changes: 42 additions & 0 deletions boards/aerotenna/ocpoc/src/i2c.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/****************************************************************************
*
* 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 <px4_arch/i2c_hw_description.h>

constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(2), // i2c-2: Air Data Probe or I2C Splitter
initI2CBusExternal(4), // i2c-4: GPS/Compass #1
initI2CBusExternal(5), // i2c-5: GPS/Compass #2
initI2CBusExternal(3), // i2c-3: GPS/Compass #3
};

42 changes: 42 additions & 0 deletions boards/aerotenna/ocpoc/src/spi.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/****************************************************************************
*
* 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 <px4_arch/spi_hw_description.h>
#include <drivers/drv_sensor.h>

constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(1, {
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, 0),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, 1),
}),
};
4 changes: 3 additions & 1 deletion boards/airmind/mindpx-v2/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,15 +33,17 @@

add_library(drivers_board
can.c
i2c.cpp
init.c
led.c
spi.c
spi.cpp
timer_config.cpp
usb.c
)

target_link_libraries(drivers_board
PRIVATE
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
Expand Down
35 changes: 6 additions & 29 deletions boards/airmind/mindpx-v2/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,13 +118,14 @@
#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 */
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 3)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#include <drivers/drv_sensor.h>
#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(PX4_SPI_BUS_EXT, 1)
#define PX4_SPIDEV_EXT0 PX4_MK_SPI_SEL(0, 0)


/* I2C busses */
Expand Down Expand Up @@ -152,29 +153,6 @@
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)

/* User GPIOs
*
* GPIO0-7 are the PWM servo outputs.
*/
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)


#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)

/* Power supply control and monitoring GPIOs */
// #define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
// #define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
Expand Down Expand Up @@ -285,7 +263,6 @@ __BEGIN_DECLS
****************************************************************************************************/

extern void stm32_spiinitialize(void);
void board_spi_reset(int ms);

extern void stm32_usbinitialize(void);

Expand Down
40 changes: 40 additions & 0 deletions boards/airmind/mindpx-v2/src/i2c.cpp
Original file line number Diff line number Diff line change
@@ -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 <px4_arch/i2c_hw_description.h>

constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusInternal(1),
initI2CBusExternal(2),
};

Loading

0 comments on commit 5a986ae

Please sign in to comment.