Cleanup SPI initialisation. Relocate mpu6500 spi configuration from
Colibri race specific code into the mpu6500 driver.
This commit is contained in:
parent
3b1f423c49
commit
7adfeffafb
1
Makefile
1
Makefile
|
@ -518,7 +518,6 @@ COLIBRI_RACE_SRC = \
|
|||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
hardware_revision.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCP_SRC)
|
||||
|
|
|
@ -94,10 +94,51 @@ static void mpu6500ReadRegister(uint8_t reg, uint8_t *data, int length)
|
|||
DISABLE_MPU6500;
|
||||
}
|
||||
|
||||
static void mpu6500SpiInit(void)
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef STM32F303xC
|
||||
RCC_AHBPeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = MPU6500_CS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_Init(MPU6500_CS_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
RCC_APB2PeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
gpio_config_t gpio;
|
||||
// CS as output
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpio.pin = MPU6500_CS_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(MPU6500_CS_GPIO, &gpio);
|
||||
#endif
|
||||
|
||||
GPIO_SetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN);
|
||||
|
||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
||||
static bool mpu6500Detect(void)
|
||||
{
|
||||
uint8_t tmp;
|
||||
|
||||
mpu6500SpiInit();
|
||||
|
||||
mpu6500ReadRegister(MPU6500_RA_WHOAMI, &tmp, 1);
|
||||
|
||||
if (tmp != MPU6500_WHO_AM_I_CONST)
|
||||
|
|
|
@ -36,16 +36,15 @@ static volatile uint16_t spi3ErrorCount = 0;
|
|||
|
||||
#ifndef SPI1_GPIO
|
||||
#define SPI1_GPIO GPIOA
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define SPI1_NSS_PIN GPIO_Pin_4
|
||||
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
|
||||
#define SPI1_SCK_PIN GPIO_Pin_5
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
|
||||
#define SPI1_SCK_CLK RCC_AHBPeriph_GPIOA
|
||||
#define SPI1_MISO_PIN GPIO_Pin_6
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
|
||||
#define SPI1_MISO_CLK RCC_AHBPeriph_GPIOA
|
||||
#define SPI1_MOSI_PIN GPIO_Pin_7
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
|
||||
#define SPI1_MOSI_CLK RCC_AHBPeriph_GPIOA
|
||||
#endif
|
||||
|
||||
void initSpi1(void)
|
||||
|
@ -72,32 +71,46 @@ void initSpi1(void)
|
|||
GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5);
|
||||
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5);
|
||||
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5);
|
||||
|
||||
#ifdef SPI1_NSS_PIN_SOURCE
|
||||
GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5);
|
||||
#endif
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
|
||||
|
||||
#ifdef SPI1_NSS_PIN
|
||||
GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef STM32F10X
|
||||
gpio_config_t gpio;
|
||||
// MOSI + SCK as output
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpio.pin = Pin_7 | Pin_5;
|
||||
gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
// MISO as input
|
||||
gpio.pin = Pin_6;
|
||||
gpio.pin = SPI1_MISO_PIN;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
#ifdef SPI1_NSS_PIN
|
||||
// NSS as gpio slave select
|
||||
gpio.pin = Pin_4;
|
||||
gpio.pin = SPI1_NSS_PIN;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Init SPI hardware
|
||||
|
@ -162,6 +175,9 @@ void initSpi2(void)
|
|||
GPIO_PinAFConfig(SPI2_GPIO, SPI2_SCK_PIN_SOURCE, GPIO_AF_5);
|
||||
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MISO_PIN_SOURCE, GPIO_AF_5);
|
||||
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MOSI_PIN_SOURCE, GPIO_AF_5);
|
||||
#ifdef SPI2_NSS_PIN_SOURCE
|
||||
GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5);
|
||||
#endif
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN | SPI2_MISO_PIN | SPI2_MOSI_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
|
@ -170,6 +186,7 @@ void initSpi2(void)
|
|||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
|
||||
|
||||
#ifdef SPI2_NSS_PIN
|
||||
GPIO_InitStructure.GPIO_Pin = SPI2_NSS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
|
@ -177,6 +194,7 @@ void initSpi2(void)
|
|||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
@ -193,10 +211,12 @@ void initSpi2(void)
|
|||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(SPI2_GPIO, &gpio);
|
||||
|
||||
#ifdef SPI2_NSS_PIN
|
||||
// NSS as gpio slave select
|
||||
gpio.pin = SPI2_NSS_PIN;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(SPI2_GPIO, &gpio);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Init SPI2 hardware
|
||||
|
|
|
@ -1,60 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/accgyro_spi_mpu6500.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
}
|
||||
|
||||
void updateHardwareRevision(void)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void spiBusInit(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
|
||||
RCC_AHBPeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = MPU6500_CS_PIN;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_Init(MPU6500_CS_GPIO, &GPIO_InitStructure);
|
||||
|
||||
GPIO_SetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN);
|
||||
|
||||
spiSetDivisor(MPU6500_SPI, SPI_9MHZ_CLOCK_DIVIDER);
|
||||
}
|
|
@ -1,21 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
void updateHardwareRevision(void);
|
||||
void detectHardwareRevision(void);
|
||||
void spiBusInit(void);
|
|
@ -18,7 +18,6 @@
|
|||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "CLBR"
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
|
||||
#define LED0_GPIO GPIOC
|
||||
#define LED0_PIN Pin_15
|
||||
|
@ -37,7 +36,6 @@
|
|||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define MPU6500_SPI SPI1
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
|
||||
#define MPU6500_CS_GPIO GPIOA
|
||||
#define MPU6500_CS_PIN GPIO_Pin_4
|
||||
|
@ -50,13 +48,10 @@
|
|||
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_SCK_PIN GPIO_Pin_3
|
||||
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
|
||||
#define SPI1_SCK_CLK RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_MISO_PIN GPIO_Pin_4
|
||||
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
|
||||
#define SPI1_MISO_CLK RCC_AHBPeriph_GPIOB
|
||||
#define SPI1_MOSI_PIN GPIO_Pin_5
|
||||
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
|
||||
#define SPI1_MOSI_CLK RCC_AHBPeriph_GPIOB
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 11
|
||||
|
||||
|
@ -74,7 +69,6 @@
|
|||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_AK8975
|
||||
//#define MAG_AK8975_ALIGN CW0_DEG_FLIP
|
||||
|
||||
#define BEEPER
|
||||
#define LED0
|
||||
|
|
|
@ -56,16 +56,19 @@
|
|||
#define NAZE_SPI_INSTANCE SPI2
|
||||
#define NAZE_SPI_CS_GPIO GPIOB
|
||||
#define NAZE_SPI_CS_PIN GPIO_Pin_12
|
||||
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
||||
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
|
||||
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
|
||||
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
||||
#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
|
||||
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
|
||||
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
||||
#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE
|
||||
|
||||
|
||||
#define USE_FLASHFS
|
||||
|
||||
#define USE_FLASH_M25P16
|
||||
|
|
Loading…
Reference in New Issue