forked from Archive/PX4-Autopilot
av/x-v1 board support cleanup and sync with fmu-v5
This commit is contained in:
parent
56591954ad
commit
db5dbb25b3
|
@ -3,6 +3,7 @@ px4_add_board(
|
|||
PLATFORM nuttx
|
||||
VENDOR av
|
||||
MODEL x-v1
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
|
@ -19,8 +20,8 @@ px4_add_board(
|
|||
DRIVERS
|
||||
barometer # all available barometer drivers
|
||||
batt_smbus
|
||||
camera_trigger
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
|
@ -31,21 +32,22 @@ px4_add_board(
|
|||
irlock
|
||||
lights/blinkm
|
||||
#lights/oreoled
|
||||
#lights/pca8574
|
||||
#lights/rgbled
|
||||
#lights/rgbled_ncp5623c
|
||||
#lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
#md25
|
||||
mkblctrl
|
||||
#lights/pca8574
|
||||
pca9685
|
||||
#pmw3901
|
||||
protocol_splitter
|
||||
#protocol_splitter
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
px4flow
|
||||
px4fmu
|
||||
rc_input
|
||||
roboclaw
|
||||
#roboclaw
|
||||
stm32
|
||||
stm32/adc
|
||||
stm32/armv7-m_dcache
|
||||
|
@ -104,7 +106,6 @@ px4_add_board(
|
|||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
#usb_connected
|
||||
ver
|
||||
|
||||
EXAMPLES
|
||||
|
|
|
@ -6,10 +6,18 @@
|
|||
|
||||
adis16477 -R 8 start
|
||||
|
||||
#adis16497 start
|
||||
|
||||
lps22hb -S start
|
||||
|
||||
lsm303agr -R 4 start
|
||||
|
||||
ms4525_airspeed -T 4515 -b 3 start
|
||||
|
||||
# TODO: try to autostart pmw3901
|
||||
# TODO: try to autostart adis16497 start
|
||||
|
||||
# Possible external compasses
|
||||
ist8310 -C -b 1 start
|
||||
ist8310 -C -b 2 start
|
||||
hmc5883 -C -T -X start
|
||||
qmc5883 -X start
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@ px4_add_library(drivers_board
|
|||
init.c
|
||||
manifest.c
|
||||
sdio.c
|
||||
spi.c
|
||||
spi.cpp
|
||||
timer_config.c
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
|
|
|
@ -54,11 +54,6 @@
|
|||
#define BOARD_HAS_NBAT_V 1 // Only one Vbat to ADC
|
||||
#define BOARD_HAS_NBAT_I 0 // No Ibat ADC
|
||||
|
||||
/* SENSORS are on SPI1, 5, 6
|
||||
* MEMORY is on bus SPI2
|
||||
* MS5611 is on bus SPI4
|
||||
*/
|
||||
|
||||
#define PX4_SPI_BUS_SENSOR1 1
|
||||
#define PX4_SPI_BUS_SENSOR2 2
|
||||
#define PX4_SPI_BUS_SENSOR4 4
|
||||
|
@ -130,27 +125,19 @@
|
|||
/* SPI1 */
|
||||
#define PX4_SPIDEV_ADIS16477 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR1,0)
|
||||
#define PX4_SENSOR1_BUS_CS_GPIO {GPIO_SPI1_CS1_ADIS16477}
|
||||
#define PX4_SENSOR1_BUS_FIRST_CS PX4_SPIDEV_ADIS16477
|
||||
#define PX4_SENSOR1_BUS_LAST_CS PX4_SPIDEV_ADIS16477
|
||||
|
||||
/* SPI2 */
|
||||
#define PX4_SPIDEV_ADIS16497 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR2,0)
|
||||
#define PX4_SENSOR2_BUS_CS_GPIO {GPIO_SPI2_CS1_ADIS16497}
|
||||
#define PX4_SENSOR2_BUS_FIRST_CS PX4_SPIDEV_ADIS16497
|
||||
#define PX4_SENSOR2_BUS_LAST_CS PX4_SPIDEV_ADIS16497
|
||||
|
||||
/* SPI4 */
|
||||
#define PX4_SPIDEV_LPS22HB PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR4,0)
|
||||
#define PX4_SENSOR4_BUS_CS_GPIO {GPIO_SPI4_CS1_LPS22HB}
|
||||
#define PX4_SENSOR4_BUS_FIRST_CS PX4_SPIDEV_LPS22HB
|
||||
#define PX4_SENSOR4_BUS_LAST_CS PX4_SPIDEV_LPS22HB
|
||||
|
||||
/* SPI5 */
|
||||
#define PX4_SPIDEV_LSM303A_M PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR5,0)
|
||||
#define PX4_SPIDEV_LSM303A_X PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR5,1)
|
||||
#define PX4_SENSOR5_BUS_CS_GPIO {GPIO_SPI5_CS1_LSM303A_M, GPIO_SPI5_CS1_LSM303A_X}
|
||||
#define PX4_SENSOR5_BUS_FIRST_CS PX4_SPIDEV_LSM303A_M
|
||||
#define PX4_SENSOR5_BUS_LAST_CS PX4_SPIDEV_LSM303A_X
|
||||
|
||||
/* I2C busses */
|
||||
#define PX4_I2C_BUS_EXPANSION 2
|
||||
|
@ -190,50 +177,9 @@
|
|||
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||
|
||||
#define ADC_BATTERY1_VOLTAGE_CHANNEL /* PA0 */ ADC1_CH(0)
|
||||
#define ADC_BATTERY1_CURRENT_CHANNEL /* PA1 */ ADC1_CH(1)
|
||||
#define ADC1_SPARE_2_CHANNEL /* PA4 */ ADC1_CH(4)
|
||||
#define ADC_RSSI_IN_CHANNEL /* PB0 */ ADC1_CH(8)
|
||||
#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10)
|
||||
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PC1 */ ADC1_CH(11)
|
||||
#define ADC_HW_VER_SENSE_CHANNEL /* PC2 */ ADC1_CH(12)
|
||||
#define ADC_HW_REV_SENSE_CHANNEL /* PC3 */ ADC1_CH(13)
|
||||
#define ADC1_SPARE_1_CHANNEL /* PC4 */ ADC1_CH(14)
|
||||
|
||||
#if BOARD_HAS_NBAT_V == 2 && BOARD_HAS_NBAT_I == 2
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_1_CHANNEL))
|
||||
#elif BOARD_HAS_NBAT_V == 1 && BOARD_HAS_NBAT_I == 1
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_1_CHANNEL))
|
||||
#elif BOARD_HAS_NBAT_V == 1 && BOARD_HAS_NBAT_I == 0
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||
(1 << ADC1_SPARE_1_CHANNEL))
|
||||
#endif
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL))
|
||||
|
||||
/* Define Battery 1 Voltage Divider and A per V
|
||||
*/
|
||||
|
@ -247,7 +193,7 @@
|
|||
|
||||
/* PWM
|
||||
*
|
||||
* 8 PWM outputs are configured.
|
||||
* 9 PWM outputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
*
|
||||
|
@ -259,6 +205,7 @@
|
|||
* FMU_CH6 : PI6 : TIM8_CH2
|
||||
* FMU_CH7 : PF7 : TIM11_CH1
|
||||
* FMU_CH8 : PF6 : TIM10_CH1
|
||||
* FMU_CH9 : PF6 : TIM4_CH3
|
||||
*
|
||||
*/
|
||||
#define GPIO_TIM1_CH1OUT /* PA8 T1C1 FMU1 */ GPIO_TIM1_CH1OUT_1
|
||||
|
@ -269,6 +216,7 @@
|
|||
#define GPIO_TIM8_CH2OUT /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2
|
||||
#define GPIO_TIM11_CH1OUT /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1OUT_2
|
||||
#define GPIO_TIM10_CH1OUT /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1OUT_2
|
||||
#define GPIO_TIM4_CH3OUT /* PD14 T4C3 FMU9 */ GPIO_TIM4_CH3OUT_1
|
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
|
@ -278,8 +226,9 @@
|
|||
#define GPIO_TIM1_CH4IN /* PA11 T1C4 FMU4 */ GPIO_TIM1_CH4IN_1
|
||||
#define GPIO_TIM2_CH4IN /* PA3 T2C4 FMU5 */ GPIO_TIM2_CH4IN_1
|
||||
#define GPIO_TIM8_CH2IN /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2
|
||||
//#define GPIO_TIM11_CH1IN /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1IN_2
|
||||
//#define GPIO_TIM10_CH1IN /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1IN_2
|
||||
#define GPIO_TIM11_CH1IN /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1IN_2
|
||||
#define GPIO_TIM10_CH1IN /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1IN_2
|
||||
#define GPIO_TIM4_CH3IN /* PD14 T4C3 FMU9 */ GPIO_TIM4_CH3IN_1
|
||||
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||
|
||||
|
@ -298,6 +247,7 @@
|
|||
#define GPIO_GPIO5_INPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_INPUT(GPIO_TIM8_CH2IN_2)
|
||||
#define GPIO_GPIO6_INPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_INPUT(GPIO_TIM11_CH1IN_2)
|
||||
#define GPIO_GPIO7_INPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_INPUT(GPIO_TIM10_CH1IN_2)
|
||||
#define GPIO_GPIO8_INPUT /* PD14 T4C3 FMU9 */ _MK_GPIO_INPUT(GPIO_TIM4_CH3IN_2)
|
||||
|
||||
#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR))
|
||||
|
||||
|
@ -309,6 +259,7 @@
|
|||
#define GPIO_GPIO5_OUTPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_OUTPUT(GPIO_TIM8_CH2OUT_2)
|
||||
#define GPIO_GPIO6_OUTPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_OUTPUT(GPIO_TIM11_CH1OUT_2)
|
||||
#define GPIO_GPIO7_OUTPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_OUTPUT(GPIO_TIM10_CH1OUT_2)
|
||||
#define GPIO_GPIO8_OUTPUT /* PF6 T10C1 FMU9 */ _MK_GPIO_OUTPUT(GPIO_TIM4_CH3OUT_2)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 5 /* use timer5 for the HRT */
|
||||
|
@ -360,6 +311,7 @@
|
|||
/* The list of GPIO that will be initialized */
|
||||
|
||||
#define PX4_GPIO_PWM_INIT_LIST { \
|
||||
GPIO_GPIO8_INPUT, \
|
||||
GPIO_GPIO7_INPUT, \
|
||||
GPIO_GPIO6_INPUT, \
|
||||
GPIO_GPIO5_INPUT, \
|
||||
|
|
|
@ -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,24 +61,17 @@
|
|||
#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 <px4_i2c.h>
|
||||
|
||||
#include "up_internal.h"
|
||||
|
||||
static int configure_switch(void);
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -238,7 +230,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 */
|
||||
|
@ -260,27 +252,16 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
|
||||
(void) board_hardfault_init(2, true);
|
||||
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
int ret = stm32_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("SPI init failed");
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
|
||||
ret = stm32_sdio_initialize();
|
||||
int ret = stm32_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("SDIO init failed");
|
||||
syslog(LOG_ERR, "[boot] SDIO init failed\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
configure_switch();
|
||||
|
||||
|
@ -302,7 +283,7 @@ static int configure_switch(void)
|
|||
struct i2c_master_s *i2c = px4_i2cbus_initialize(PX4_I2C_BUS_ONBOARD);
|
||||
|
||||
if (i2c == NULL) {
|
||||
PX4_ERR("I2C device not opened");
|
||||
syslog(LOG_ERR, "[boot] I2C device not opened\n");
|
||||
}
|
||||
|
||||
// ethernet switch enable
|
||||
|
@ -327,7 +308,7 @@ static int configure_switch(void)
|
|||
break;
|
||||
|
||||
} else {
|
||||
PX4_ERR("ETH switch I2C fail: %d, retrying", ret);
|
||||
syslog(LOG_ERR, "[boot] ETH switch I2C fail: %d, retrying\n", ret);
|
||||
}
|
||||
|
||||
/* if we have already retried once, or we are going to give up, then reset the bus */
|
||||
|
|
|
@ -46,10 +46,11 @@
|
|||
* 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"
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_rc_input
|
||||
|
|
|
@ -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>
|
||||
|
@ -137,7 +137,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;
|
||||
}
|
||||
|
||||
|
@ -148,7 +148,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,428 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2018 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_SENSOR1_BUS_CS_GPIO;
|
||||
static const uint32_t spi2selects_gpio[] = PX4_SENSOR2_BUS_CS_GPIO;
|
||||
static const uint32_t spi4selects_gpio[] = PX4_SENSOR4_BUS_CS_GPIO;
|
||||
static const uint32_t spi5selects_gpio[] = PX4_SENSOR5_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)
|
||||
{
|
||||
board_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
|
||||
board_gpio_init(spi2selects_gpio, arraySize(spi2selects_gpio));
|
||||
board_gpio_init(spi4selects_gpio, arraySize(spi4selects_gpio));
|
||||
board_gpio_init(spi5selects_gpio, arraySize(spi5selects_gpio));
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI buses on PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
static struct spi_dev_s *spi_sensor1;
|
||||
static struct spi_dev_s *spi_sensor2;
|
||||
static struct spi_dev_s *spi_sensor4;
|
||||
static struct spi_dev_s *spi_sensor5;
|
||||
|
||||
__EXPORT int stm32_spi_bus_initialize(void)
|
||||
{
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
|
||||
/* Get the SPI port for the Sensors */
|
||||
spi_sensor1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR1);
|
||||
|
||||
if (!spi_sensor1) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR1);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default PX4_SPI_BUS_SENSORS to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi_sensor1, 1000000);
|
||||
SPI_SETBITS(spi_sensor1, 16);
|
||||
SPI_SETMODE(spi_sensor1, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_SENSOR1_BUS_FIRST_CS; cs <= PX4_SENSOR1_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_sensor1, cs, false);
|
||||
}
|
||||
|
||||
|
||||
/* Get the SPI port for the Memory */
|
||||
spi_sensor2 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR2);
|
||||
|
||||
if (!spi_sensor2) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR2);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default PX4_SPI_BUS_SENSOR2 to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi_sensor2, 1000000);
|
||||
SPI_SETBITS(spi_sensor2, 8);
|
||||
SPI_SETMODE(spi_sensor2, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_SENSOR2_BUS_FIRST_CS; cs <= PX4_SENSOR2_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_sensor2, cs, false);
|
||||
}
|
||||
|
||||
|
||||
/* Get the SPI port for the BARO */
|
||||
spi_sensor4 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR4);
|
||||
|
||||
if (!spi_sensor4) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR4);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
SPI_SETFREQUENCY(spi_sensor4, 1 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_sensor4, 8);
|
||||
SPI_SETMODE(spi_sensor4, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_SENSOR4_BUS_FIRST_CS; cs <= PX4_SENSOR4_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_sensor4, cs, false);
|
||||
}
|
||||
|
||||
|
||||
/* Get the SPI port for the PX4_SPI_EXTERNAL1 */
|
||||
spi_sensor5 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR5);
|
||||
|
||||
if (!spi_sensor5) {
|
||||
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR5);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
SPI_SETFREQUENCY(spi_sensor5, 1 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_sensor5, 8);
|
||||
SPI_SETMODE(spi_sensor5, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_SENSOR5_BUS_FIRST_CS; cs <= PX4_SENSOR5_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_sensor5, 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_SENSOR1);
|
||||
|
||||
/* 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;
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSOR2);
|
||||
|
||||
/* 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_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_SENSOR4);
|
||||
|
||||
/* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__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_SENSOR5);
|
||||
|
||||
/* 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;
|
||||
}
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_spi_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
/* disable SPI bus */
|
||||
|
||||
// SPI1
|
||||
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);
|
||||
|
||||
// SPI2
|
||||
for (size_t cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||
if (spi2selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(_PIN_OFF(spi2selects_gpio[cs]));
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI2_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI2_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI2_MOSI_OFF);
|
||||
|
||||
// SPI4
|
||||
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||
if (spi4selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(_PIN_OFF(spi4selects_gpio[cs]));
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI4_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI4_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI4_MOSI_OFF);
|
||||
|
||||
// SPI5
|
||||
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||
if (spi5selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(_PIN_OFF(spi5selects_gpio[cs]));
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI5_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI5_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI5_MOSI_OFF);
|
||||
|
||||
|
||||
/* wait for the sensor rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
PX4_INFO("reset done, %d ms", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
|
||||
// SPI1
|
||||
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);
|
||||
|
||||
// SPI2
|
||||
for (size_t cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||
if (spi2selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(spi2selects_gpio[cs]);
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI2_SCK);
|
||||
stm32_configgpio(GPIO_SPI2_MISO);
|
||||
stm32_configgpio(GPIO_SPI2_MOSI);
|
||||
|
||||
// SPI4
|
||||
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||
if (spi4selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(spi4selects_gpio[cs]);
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI4_SCK);
|
||||
stm32_configgpio(GPIO_SPI4_MISO);
|
||||
stm32_configgpio(GPIO_SPI4_MOSI);
|
||||
|
||||
// SPI5
|
||||
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||
if (spi5selects_gpio[cs] != 0) {
|
||||
stm32_configgpio(spi5selects_gpio[cs]);
|
||||
}
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI5_SCK);
|
||||
stm32_configgpio(GPIO_SPI5_MISO);
|
||||
stm32_configgpio(GPIO_SPI5_MOSI);
|
||||
|
||||
}
|
|
@ -0,0 +1,336 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2018 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>
|
||||
|
||||
/* Define CS GPIO array */
|
||||
static constexpr uint32_t spi1selects_gpio[] = PX4_SENSOR1_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi2selects_gpio[] = PX4_SENSOR2_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi4selects_gpio[] = PX4_SENSOR4_BUS_CS_GPIO;
|
||||
static constexpr uint32_t spi5selects_gpio[] = PX4_SENSOR5_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
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* 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_SENSOR1);
|
||||
|
||||
// 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)
|
||||
{
|
||||
ASSERT(PX4_SPI_BUS_ID(devid) == PX4_SPI_BUS_SENSOR2);
|
||||
|
||||
// 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
|
||||
|
||||
/************************************************************************************
|
||||
* 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_SENSOR4);
|
||||
|
||||
// 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_SENSOR5);
|
||||
|
||||
// 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: board_spi_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
|
||||
// disable SPI1
|
||||
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);
|
||||
#endif // CONFIG_STM32F7_SPI1
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI2
|
||||
|
||||
// disable SPI2
|
||||
for (auto cs : spi2selects_gpio) {
|
||||
stm32_configgpio(_PIN_OFF(cs));
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI2_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI2_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI2_MOSI_OFF);
|
||||
#endif // CONFIG_STM32F7_SPI2
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
|
||||
// disable SPI4
|
||||
for (auto cs : spi4selects_gpio) {
|
||||
stm32_configgpio(_PIN_OFF(cs));
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI4_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI4_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI4_MOSI_OFF);
|
||||
#endif // CONFIG_STM32F7_SPI4
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
|
||||
// disable SPI5
|
||||
for (auto cs : spi5selects_gpio) {
|
||||
stm32_configgpio(_PIN_OFF(cs));
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI5_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI5_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI5_MOSI_OFF);
|
||||
#endif // CONFIG_STM32F7_SPI5
|
||||
|
||||
|
||||
/* wait for the sensor rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI1
|
||||
|
||||
// re-enable SPI1
|
||||
for (auto cs : spi1selects_gpio) {
|
||||
stm32_configgpio(cs);
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK);
|
||||
stm32_configgpio(GPIO_SPI1_MISO);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI);
|
||||
#endif // CONFIG_STM32F7_SPI1
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI2
|
||||
|
||||
// re-enable SPI2
|
||||
for (auto cs : spi2selects_gpio) {
|
||||
stm32_configgpio(cs);
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI2_SCK);
|
||||
stm32_configgpio(GPIO_SPI2_MISO);
|
||||
stm32_configgpio(GPIO_SPI2_MOSI);
|
||||
#endif // CONFIG_STM32F7_SPI2
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI4
|
||||
|
||||
// re-enable SPI4
|
||||
for (auto cs : spi4selects_gpio) {
|
||||
stm32_configgpio(cs);
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI4_SCK);
|
||||
stm32_configgpio(GPIO_SPI4_MISO);
|
||||
stm32_configgpio(GPIO_SPI4_MOSI);
|
||||
#endif // CONFIG_STM32F7_SPI4
|
||||
|
||||
#ifdef CONFIG_STM32F7_SPI5
|
||||
|
||||
// re-enable SPI5
|
||||
for (auto cs : spi5selects_gpio) {
|
||||
stm32_configgpio(cs);
|
||||
}
|
||||
|
||||
stm32_configgpio(GPIO_SPI5_SCK);
|
||||
stm32_configgpio(GPIO_SPI5_MISO);
|
||||
stm32_configgpio(GPIO_SPI5_MOSI);
|
||||
#endif // CONFIG_STM32F7_SPI5
|
||||
}
|
|
@ -60,35 +60,34 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
|||
.last_channel_index = 3,
|
||||
.handler = io_timer_handler0,
|
||||
.vectorno = STM32_IRQ_TIM1CC,
|
||||
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM2_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM2EN,
|
||||
.clock_freq = STM32_APB1_TIM2_CLKIN,
|
||||
.first_channel_index = 3,
|
||||
.last_channel_index = 3,
|
||||
.first_channel_index = 4,
|
||||
.last_channel_index = 4,
|
||||
.handler = io_timer_handler1,
|
||||
.vectorno = STM32_IRQ_TIM2,
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM8_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM10EN,
|
||||
.clock_freq = STM32_APB2_TIM8_CLKIN,
|
||||
.first_channel_index = 3,
|
||||
.last_channel_index = 3,
|
||||
.first_channel_index = 5,
|
||||
.last_channel_index = 5,
|
||||
.handler = io_timer_handler2,
|
||||
.vectorno = STM32_IRQ_TIM8CC, // REVIEW
|
||||
.vectorno = STM32_IRQ_TIM8CC,
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM11_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM11EN,
|
||||
.clock_freq = STM32_APB2_TIM11_CLKIN,
|
||||
.first_channel_index = 2,
|
||||
.last_channel_index = 2,
|
||||
.first_channel_index = 6,
|
||||
.last_channel_index = 6,
|
||||
.handler = io_timer_handler3,
|
||||
.vectorno = STM32_IRQ_TIM11,
|
||||
},
|
||||
|
@ -97,12 +96,21 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
|||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM10EN,
|
||||
.clock_freq = STM32_APB2_TIM10_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 0,
|
||||
.first_channel_index = 7,
|
||||
.last_channel_index = 7,
|
||||
.handler = io_timer_handler4,
|
||||
.vectorno = STM32_IRQ_TIM10,
|
||||
|
||||
}
|
||||
},
|
||||
// {
|
||||
// .base = STM32_TIM4_BASE,
|
||||
// .clock_register = STM32_RCC_APB1ENR,
|
||||
// .clock_bit = RCC_APB1ENR_TIM4EN,
|
||||
// .clock_freq = STM32_APB1_TIM4_CLKIN,
|
||||
// .first_channel_index = 8,
|
||||
// .last_channel_index = 8,
|
||||
// .handler = io_timer_handler5,
|
||||
// .vectorno = STM32_IRQ_TIM4,
|
||||
// }
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
|
@ -154,20 +162,28 @@ __EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
|||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
// {
|
||||
// .gpio_out = GPIO_TIM11_CH1OUT,
|
||||
// .gpio_in = GPIO_TIM11_CH1IN,
|
||||
// .timer_index = 3,
|
||||
// .timer_channel = 1,
|
||||
// .ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
// .masks = GTIM_SR_CC1IF | GTIM_SR_CC1F
|
||||
// },
|
||||
// {
|
||||
// .gpio_out = GPIO_TIM10_CH1OUT,
|
||||
// .gpio_in = GPIO_TIM10_CH1IN,
|
||||
// .timer_index = 4,
|
||||
// .timer_channel = 1,
|
||||
// .ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
// .masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
// }
|
||||
{
|
||||
.gpio_out = GPIO_TIM11_CH1OUT,
|
||||
.gpio_in = GPIO_TIM11_CH1IN,
|
||||
.timer_index = 3,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM10_CH1OUT,
|
||||
.gpio_in = GPIO_TIM10_CH1IN,
|
||||
.timer_index = 4,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
// {
|
||||
// .gpio_out = GPIO_TIM4_CH3OUT,
|
||||
// .gpio_in = GPIO_TIM4_CH3IN,
|
||||
// .timer_index = 5,
|
||||
// .timer_channel = 3,
|
||||
// .ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
// .masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
// }
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue