forked from Archive/PX4-Autopilot
px4_fmu-v5 board spi cleanup
This commit is contained in:
parent
c6edf41a74
commit
06f5a782f4
|
@ -27,11 +27,10 @@ px4_add_board(
|
|||
#heater
|
||||
imu/adis16448
|
||||
#imu # all available imu drivers
|
||||
imu/bma180
|
||||
imu/bmi055
|
||||
imu/bmi160
|
||||
imu/mpu6000
|
||||
imu/mpu9250
|
||||
imu/icm20948
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/oreoled
|
||||
|
|
|
@ -31,13 +31,13 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_library(drivers_board
|
||||
#stm32_can.c # WIP
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
init.c
|
||||
led.c
|
||||
manifest.c
|
||||
sdio.c
|
||||
spi.c
|
||||
spi.cpp
|
||||
timer_config.c
|
||||
usb.c
|
||||
)
|
||||
|
|
|
@ -121,6 +121,8 @@
|
|||
#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 */
|
||||
|
||||
|
@ -170,7 +172,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 SPIAUX_CS_MEM /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5)
|
||||
|
||||
|
||||
/*
|
||||
|
@ -186,45 +187,31 @@
|
|||
|
||||
/* 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 */
|
||||
|
||||
|
||||
#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,0)
|
||||
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,1)
|
||||
#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,2)
|
||||
#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,3)
|
||||
|
||||
#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS2_ICM20602, GPIO_SPI1_CS3_BMI055_GYRO, GPIO_SPI1_CS4_BMI055_ACC}
|
||||
#define PX4_SENSORS_BUS_FIRST_CS PX4_SPIDEV_ICM_20689
|
||||
#define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_BMI055_ACC
|
||||
#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,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 PX4_MK_SPI_SEL(PX4_SPI_BUS_MEMORY,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(PX4_SPI_BUS_BARO,0)
|
||||
#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_BARO_BUS_FIRST_CS PX4_SPIDEV_BARO
|
||||
#define PX4_BARO_BUS_LAST_CS PX4_SPIDEV_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_EXTERNAL1_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL1_1
|
||||
#define PX4_EXTERNAL1_BUS_LAST_CS PX4_SPIDEV_EXTERNAL1_3
|
||||
|
||||
#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_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL2,3)
|
||||
#define PX4_EXTERNAL2_BUS_CS_GPIO {SPI6_CS1_EXTERNAL2, SPI6_CS2_EXTERNAL2, SPI6_CS3_EXTERNAL2, SPIAUX_CS_MEM}
|
||||
#define PX4_EXTERNAL2_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL2_1
|
||||
#define PX4_EXTERNAL2_BUS_LAST_CS PX4_SPIDEV_AUX_MEM
|
||||
#define PX4_EXTERNAL2_BUS_CS_GPIO {SPI6_CS1_EXTERNAL2, SPI6_CS2_EXTERNAL2, SPI6_CS3_EXTERNAL2}
|
||||
|
||||
|
||||
/* I2C busses */
|
||||
|
@ -734,16 +721,6 @@ int stm32_sdio_initialize(void);
|
|||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI Buses.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
extern int stm32_spi_bus_initialize(void);
|
||||
|
||||
void board_spi_reset(int ms);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
|
|
@ -37,16 +37,12 @@
|
|||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can.h>
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
|
@ -81,6 +77,7 @@
|
|||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
|
@ -127,3 +124,5 @@ int can_devinit(void)
|
|||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_CAN */
|
||||
|
|
|
@ -45,9 +45,7 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <px4_log.h>
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
@ -55,6 +53,7 @@
|
|||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
|
@ -62,22 +61,16 @@
|
|||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
|
||||
#include <chip.h>
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include "up_internal.h"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <px4_init.h>
|
||||
|
||||
#include "up_internal.h"
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
@ -295,10 +288,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
|
||||
|
||||
if (OK == board_determine_hw_info()) {
|
||||
PX4_INFO("Rev 0x%1x : Ver 0x%1x %s", board_get_hw_revision(), board_get_hw_version(), board_get_hw_type_name());
|
||||
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
|
||||
board_get_hw_type_name());
|
||||
|
||||
} else {
|
||||
PX4_ERR("Failed to read HW revision and version");
|
||||
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
|
||||
}
|
||||
|
||||
px4_platform_init();
|
||||
|
@ -306,7 +300,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
PX4_ERR("DMA alloc FAILED");
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
|
@ -337,26 +331,15 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
int ret = stm32_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
|
||||
ret = stm32_sdio_initialize();
|
||||
int ret = stm32_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
|
@ -46,10 +46,12 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "systemlib/px4_macros.h"
|
||||
#include "px4_log.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
|
@ -137,7 +139,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
PX4_ERR("Board %4x is not supported!", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %4x is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -36,8 +36,8 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
|
@ -141,7 +141,7 @@ int stm32_sdio_initialize(void)
|
|||
sdio_dev = sdio_initialize(SDIO_SLOTNO);
|
||||
|
||||
if (!sdio_dev) {
|
||||
PX4_ERR("[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
|
@ -152,7 +152,7 @@ int stm32_sdio_initialize(void)
|
|||
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
|
|
@ -1,508 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
/* Define CS GPIO array */
|
||||
static const uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO;
|
||||
static const uint32_t spi2selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
|
||||
#ifdef CONFIG_STM32F7_SPI3
|
||||
static const uint32_t spi3selects_gpio[] = {FIXME};
|
||||
#error Need to define SPI3 Usage
|
||||
#endif
|
||||
static const uint32_t spi4selects_gpio[] = PX4_BARO_BUS_CS_GPIO;
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
static const uint32_t spi5selects_gpio[] = PX4_EXTERNAL1_BUS_CS_GPIO;
|
||||
#endif
|
||||
static const uint32_t spi6selects_gpio[] = PX4_EXTERNAL2_BUS_CS_GPIO;
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spiinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
board_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI2
|
||||
board_gpio_init(spi2selects_gpio, arraySize(spi2selects_gpio));
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI3
|
||||
board_gpio_init(spi3selects_gpio, arraySize(spi3selects_gpio));
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
board_gpio_init(spi4selects_gpio, arraySize(spi4selects_gpio));
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
board_gpio_init(spi5selects_gpio, arraySize(spi5selects_gpio));
|
||||
#endif
|
||||
#ifdef CONFIG_STM32F7_SPI6
|
||||
board_gpio_init(spi6selects_gpio, arraySize(spi6selects_gpio));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI buses on PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
static struct spi_dev_s *spi_sensors;
|
||||
static struct spi_dev_s *spi_memory;
|
||||
static struct spi_dev_s *spi_baro;
|
||||
static struct spi_dev_s *spi_ext;
|
||||
|
||||
__EXPORT int stm32_spi_bus_initialize(void)
|
||||
{
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
/* Get the SPI port for the Sensors */
|
||||
|
||||
spi_sensors = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
|
||||
|
||||
if (!spi_sensors) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default PX4_SPI_BUS_SENSORS to 1MHz and de-assert the known chip selects. */
|
||||
|
||||
SPI_SETFREQUENCY(spi_sensors, 10000000);
|
||||
SPI_SETBITS(spi_sensors, 8);
|
||||
SPI_SETMODE(spi_sensors, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_SENSORS_BUS_FIRST_CS; cs <= PX4_SENSORS_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_sensors, cs, false);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the Memory */
|
||||
|
||||
spi_memory = stm32_spibus_initialize(PX4_SPI_BUS_MEMORY);
|
||||
|
||||
if (!spi_memory) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_MEMORY);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default PX4_SPI_BUS_MEMORY to 12MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_memory, 12 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_memory, 8);
|
||||
SPI_SETMODE(spi_memory, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_MEMORY_BUS_FIRST_CS; cs <= PX4_MEMORY_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_memory, cs, false);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the BARO */
|
||||
|
||||
spi_baro = stm32_spibus_initialize(PX4_SPI_BUS_BARO);
|
||||
|
||||
if (!spi_baro) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_BARO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* MS5611 has max SPI clock speed of 20MHz
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_baro, 20 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_baro, 8);
|
||||
SPI_SETMODE(spi_baro, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_BARO_BUS_FIRST_CS; cs <= PX4_BARO_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_baro, cs, false);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the PX4_SPI_EXTERNAL1 */
|
||||
|
||||
spi_ext = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);
|
||||
|
||||
if (!spi_ext) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_ext, 8);
|
||||
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_EXTERNAL1_BUS_FIRST_CS; cs <= PX4_EXTERNAL1_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_ext, cs, false);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the PX4_SPI_EXTERNAL2 */
|
||||
|
||||
spi_ext = stm32_spibus_initialize(PX4_SPI_BUS_EXTERNAL2);
|
||||
|
||||
if (!spi_ext) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL2);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_ext, 8);
|
||||
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_EXTERNAL2_BUS_FIRST_CS; cs <= PX4_EXTERNAL2_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_ext, cs, false);
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi1select and stm32_spi1status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 1.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spi1select(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_SENSORS);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||
if (spi1selects_gpio[cs] != 0) {
|
||||
stm32_gpiowrite(spi1selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi1selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi2select and stm32_spi2status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 2.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_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;
|
||||
|
||||
if (devid == SPIDEV_FLASH(0)) {
|
||||
sel = PX4_SPIDEV_MEMORY;
|
||||
}
|
||||
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_MEMORY);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (int cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||
if (spi2selects_gpio[cs] != 0) {
|
||||
stm32_gpiowrite(spi2selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi2selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi3select and stm32_spi2status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 3.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI3
|
||||
__EXPORT void stm32_spi3select(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) == FIXME);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (int cs = 0; arraySize(spi3selects_gpio) > 1 && cs < arraySize(spi3selects_gpio); cs++) {
|
||||
if (spi3selects_gpio[cs] != 0) {
|
||||
stm32_gpiowrite(spi3selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi3selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi4select and stm32_spi4status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 4.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
int sel = (int) devid;
|
||||
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_BARO);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||
stm32_gpiowrite(spi4selects_gpio[cs], 1);
|
||||
}
|
||||
|
||||
uint32_t gpio = spi4selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi5select and stm32_spi5status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 5.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
__EXPORT void stm32_spi5select(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_EXTERNAL1);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||
stm32_gpiowrite(spi5selects_gpio[cs], 1);
|
||||
}
|
||||
|
||||
uint32_t gpio = spi5selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi6select and stm32_spi6status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 6.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spi6select(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_EXTERNAL2);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
for (size_t cs = 0; arraySize(spi6selects_gpio) > 1 && cs < arraySize(spi6selects_gpio); cs++) {
|
||||
stm32_gpiowrite(spi6selects_gpio[cs], 1);
|
||||
}
|
||||
|
||||
uint32_t gpio = spi6selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
stm32_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_spi_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
/* disable SPI bus */
|
||||
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||
if (spi1selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(_PIN_OFF(spi1selects_gpio[cs]));
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
|
||||
|
||||
|
||||
#if BOARD_USE_DRDY
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY5_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY6_BMI055_ACC);
|
||||
#endif
|
||||
/* set the sensor rail off */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
|
||||
|
||||
/* wait for the sensor rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the sensor rail back on */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||
if (spi1selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(spi1selects_gpio[cs]);
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK);
|
||||
stm32_configgpio(GPIO_SPI1_MISO);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI);
|
||||
|
||||
#if BOARD_USE_DRDY
|
||||
stm32_configgpio(GPIO_SPI1_DRDY1_ICM20689);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY2_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY3_BMI055_ACC);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY4_ICM20602);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY5_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY6_BMI055_ACC);
|
||||
#endif
|
||||
|
||||
}
|
|
@ -0,0 +1,321 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/* Define CS GPIO array */
|
||||
static constexpr uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi2selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi4selects_gpio[] = PX4_BARO_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi5selects_gpio[] = PX4_EXTERNAL1_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi6selects_gpio[] = PX4_EXTERNAL2_BUS_CS_GPIO;
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spiinitialize()
|
||||
{
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
|
||||
for (auto gpio : spi1selects_gpio) {
|
||||
px4_arch_configgpio(gpio);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32F7_SPI1
|
||||
|
||||
|
||||
#if defined(CONFIG_STM32F7_SPI2)
|
||||
|
||||
for (auto gpio : spi2selects_gpio) {
|
||||
px4_arch_configgpio(gpio);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32F7_SPI2
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
|
||||
for (auto gpio : spi4selects_gpio) {
|
||||
px4_arch_configgpio(gpio);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32F7_SPI4
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
|
||||
for (auto gpio : spi5selects_gpio) {
|
||||
px4_arch_configgpio(gpio);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32F7_SPI5
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI6
|
||||
|
||||
for (auto gpio : spi6selects_gpio) {
|
||||
px4_arch_configgpio(gpio);
|
||||
}
|
||||
|
||||
#endif // CONFIG_STM32F7_SPI6
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi1select and stm32_spi1status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 1.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_SENSORS);
|
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi1selects_gpio) {
|
||||
stm32_gpiowrite(cs, 1);
|
||||
}
|
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi1selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32F7_SPI1
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi2select and stm32_spi2status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 2.
|
||||
*
|
||||
************************************************************************************/
|
||||
#if defined(CONFIG_STM32F7_SPI2)
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
if (devid == SPIDEV_FLASH(0)) {
|
||||
devid = PX4_SPIDEV_MEMORY;
|
||||
}
|
||||
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_MEMORY);
|
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi2selects_gpio) {
|
||||
stm32_gpiowrite(cs, 1);
|
||||
}
|
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi2selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32F7_SPI2 && GPIO_SPI2_CS_FRAM
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi4select and stm32_spi4status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 4.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_BARO);
|
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi4selects_gpio) {
|
||||
stm32_gpiowrite(cs, 1);
|
||||
}
|
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi4selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32F7_SPI4
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi5select and stm32_spi5status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 5.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_EXTERNAL1);
|
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi5selects_gpio) {
|
||||
stm32_gpiowrite(cs, 1);
|
||||
}
|
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi5selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32F7_SPI5
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi6select and stm32_spi6status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 6.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_STM32F7_SPI6
|
||||
__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_EXTERNAL2);
|
||||
|
||||
// Making sure the other peripherals are not selected
|
||||
for (auto cs : spi6selects_gpio) {
|
||||
stm32_gpiowrite(cs, 1);
|
||||
}
|
||||
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
stm32_gpiowrite(spi6selects_gpio[PX4_SPI_DEV_ID(devid)], !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif // CONFIG_STM32F7_SPI6
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_spi_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
// disable SPI bus
|
||||
for (auto cs : spi1selects_gpio) {
|
||||
stm32_configgpio(_PIN_OFF(cs));
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
|
||||
|
||||
|
||||
#if BOARD_USE_DRDY
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY5_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY6_BMI055_ACC);
|
||||
#endif
|
||||
/* set the sensor rail off */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
|
||||
|
||||
/* wait for the sensor rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the sensor rail back on */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
for (auto cs : spi1selects_gpio) {
|
||||
stm32_configgpio(cs);
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK);
|
||||
stm32_configgpio(GPIO_SPI1_MISO);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI);
|
||||
|
||||
#if BOARD_USE_DRDY
|
||||
stm32_configgpio(GPIO_SPI1_DRDY1_ICM20689);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY2_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY3_BMI055_ACC);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY4_ICM20602);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY5_BMI055_GYRO);
|
||||
stm32_configgpio(GPIO_SPI1_DRDY6_BMI055_ACC);
|
||||
#endif
|
||||
}
|
|
@ -20,37 +20,36 @@ px4_add_board(
|
|||
DRIVERS
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
lights/blinkm
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/adis16448
|
||||
#imu # all available imu drivers
|
||||
imu/bmi055
|
||||
#imu/bmi160
|
||||
#imu/bma180
|
||||
imu/mpu6000
|
||||
#imu/mpu9250
|
||||
irlock
|
||||
imu/mpu9250
|
||||
imu/icm20948
|
||||
#irlock
|
||||
#lights/blinkm
|
||||
#lights/oreoled
|
||||
lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
#md25
|
||||
mkblctrl
|
||||
lights/oreoled
|
||||
lights/pca8574
|
||||
pca9685
|
||||
pmw3901
|
||||
protocol_splitter
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
pwm_out_sim
|
||||
px4flow
|
||||
px4fmu
|
||||
px4io
|
||||
rc_input
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
|
@ -80,6 +79,7 @@ px4_add_board(
|
|||
mavlink
|
||||
mc_att_control
|
||||
mc_pos_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
sensors
|
||||
vmount
|
||||
|
@ -118,6 +118,7 @@ px4_add_board(
|
|||
#hello
|
||||
#hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
#position_estimator_inav
|
||||
#px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values
|
||||
#px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
|
||||
#rover_steering_control # Rover example app
|
||||
|
|
Loading…
Reference in New Issue