STM32F4: Main, Sensors, io

This commit is contained in:
blckmn 2016-06-08 05:36:46 +10:00
parent de2c382ba9
commit 96757c18a2
6 changed files with 79 additions and 21 deletions

View File

@ -56,6 +56,8 @@ typedef enum {
SERIAL_PORT_USART2, SERIAL_PORT_USART2,
SERIAL_PORT_USART3, SERIAL_PORT_USART3,
SERIAL_PORT_USART4, SERIAL_PORT_USART4,
SERIAL_PORT_USART5,
SERIAL_PORT_USART6,
SERIAL_PORT_USB_VCP = 20, SERIAL_PORT_USB_VCP = 20,
SERIAL_PORT_SOFTSERIAL1 = 30, SERIAL_PORT_SOFTSERIAL1 = 30,
SERIAL_PORT_SOFTSERIAL2, SERIAL_PORT_SOFTSERIAL2,

View File

@ -220,7 +220,7 @@ static const char * const sensorTypeNames[] = {
#define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG) #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
static const char * const sensorHardwareNames[4][11] = { static const char * const sensorHardwareNames[4][11] = {
{ "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL }, { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE", NULL },
{ "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL }, { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
{ "", "None", "BMP085", "MS5611", "BMP280", NULL }, { "", "None", "BMP085", "MS5611", "BMP280", NULL },
{ "", "None", "HMC5883", "AK8975", "AK8963", NULL } { "", "None", "HMC5883", "AK8975", "AK8963", NULL }

View File

@ -135,13 +135,11 @@ void spektrumBind(rxConfig_t *rxConfig);
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig); const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
void sonarInit(const sonarHardware_t *sonarHardware); void sonarInit(const sonarHardware_t *sonarHardware);
#ifdef STM32F303xC
// from system_stm32f30x.c
void SetSysClock(void);
#endif
#ifdef STM32F10X #ifdef STM32F10X
// from system_stm32f10x.c // from system_stm32f10x.c
void SetSysClock(bool overclock); void SetSysClock(bool overclock);
#else
void SetSysClock(void);
#endif #endif
typedef enum { typedef enum {
@ -169,19 +167,20 @@ void init(void)
systemState |= SYSTEM_STATE_CONFIG_LOADED; systemState |= SYSTEM_STATE_CONFIG_LOADED;
#ifdef STM32F303 #ifdef STM32F3
// start fpu // start fpu
SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2)); SCB->CPACR = (0x3 << (10*2)) | (0x3 << (11*2));
#endif
#ifdef STM32F303xC
SetSysClock(); SetSysClock();
#endif #endif
#ifdef STM32F10X #ifdef STM32F1
// Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers
// Configure the Flash Latency cycles and enable prefetch buffer // Configure the Flash Latency cycles and enable prefetch buffer
SetSysClock(0); // TODO - Remove from config in the future SetSysClock(0); // TODO - Remove from config in the future
#endif #endif
#ifdef STM32F4
SetSysClock();
#endif
//i2cSetOverclock(masterConfig.i2c_overclock); //i2cSetOverclock(masterConfig.i2c_overclock);
systemInit(); systemInit();
@ -198,19 +197,21 @@ void init(void)
// initialize IO (needed for all IO operations) // initialize IO (needed for all IO operations)
IOInitGlobal(); IOInitGlobal();
#ifdef USE_EXTI
EXTIInit();
#endif
#ifdef ALIENFLIGHTF3 #ifdef ALIENFLIGHTF3
if (hardwareRevision == AFF3_REV_1) { if (hardwareRevision == AFF3_REV_1) {
ledInit(false); ledInit(false);
} else { }
else {
ledInit(true); ledInit(true);
} }
#else #else
ledInit(false); ledInit(false);
#endif #endif
LED2_ON;
#ifdef USE_EXTI
EXTIInit();
#endif
#ifdef SPRACINGF3MINI #ifdef SPRACINGF3MINI
gpio_config_t buttonAGpioConfig = { gpio_config_t buttonAGpioConfig = {
@ -302,6 +303,12 @@ void init(void)
#ifdef STM32F303xC #ifdef STM32F303xC
pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3); pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
#endif #endif
#if defined(USE_USART2) && defined(STM32F40_41xxx)
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
#endif
#if defined(USE_USART6) && defined(STM32F40_41xxx)
pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6);
#endif
pwm_params.useVbat = feature(FEATURE_VBAT); pwm_params.useVbat = feature(FEATURE_VBAT);
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM); pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
@ -431,7 +438,6 @@ void init(void)
} }
#endif #endif
#ifdef USE_I2C #ifdef USE_I2C
#if defined(NAZE) #if defined(NAZE)
if (hardwareRevision != NAZE32_SP) { if (hardwareRevision != NAZE32_SP) {
@ -477,7 +483,13 @@ void init(void)
} }
#endif #endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, masterConfig.mag_declination, masterConfig.gyro_lpf, masterConfig.gyro_sync_denom)) { if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
masterConfig.acc_hardware,
masterConfig.mag_hardware,
masterConfig.baro_hardware,
masterConfig.mag_declination,
masterConfig.gyro_lpf,
masterConfig.gyro_sync_denom)) {
// if gyro was not detected due to whatever reason, we give up now. // if gyro was not detected due to whatever reason, we give up now.
failureMode(FAILURE_MISSING_ACC); failureMode(FAILURE_MISSING_ACC);
} }
@ -486,6 +498,8 @@ void init(void)
LED1_ON; LED1_ON;
LED0_OFF; LED0_OFF;
LED2_OFF;
for (i = 0; i < 10; i++) { for (i = 0; i < 10; i++) {
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;
@ -670,7 +684,8 @@ void processLoopback(void) {
#define processLoopback() #define processLoopback()
#endif #endif
void main_init(void) { void main_init(void)
{
init(); init();
/* Setup scheduler */ /* Setup scheduler */
@ -771,7 +786,8 @@ int main(void)
* cause of the fault. * cause of the fault.
* The function ends with a BKPT instruction to force control back into the debugger * The function ends with a BKPT instruction to force control back into the debugger
*/ */
void hard_fault_handler_c(unsigned long *hardfault_args){ void hard_fault_handler_c(unsigned long *hardfault_args)
{
volatile unsigned long stacked_r0 ; volatile unsigned long stacked_r0 ;
volatile unsigned long stacked_r1 ; volatile unsigned long stacked_r1 ;
volatile unsigned long stacked_r2 ; volatile unsigned long stacked_r2 ;
@ -822,6 +838,8 @@ void hard_fault_handler_c(unsigned long *hardfault_args){
#else #else
void HardFault_Handler(void) void HardFault_Handler(void)
{ {
LED2_ON;
// fall out of the sky // fall out of the sky
uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY; uint8_t requiredStateForMotors = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_MOTORS_READY;
if ((systemState & requiredStateForMotors) == requiredStateForMotors) { if ((systemState & requiredStateForMotors) == requiredStateForMotors) {
@ -835,6 +853,14 @@ void HardFault_Handler(void)
} }
#endif #endif
while (1); LED1_OFF;
LED0_OFF;
while (1) {
#ifdef LED2
delay(50);
LED2_TOGGLE;
#endif
}
} }
#endif #endif

View File

@ -17,6 +17,20 @@
#pragma once #pragma once
#if defined(STM32F40_41xxx) || defined (STM32F411xE)
#include "stm32f4xx_conf.h"
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_gpio.h"
#include "core_cm4.h"
// Chip Unique ID on F405
#define U_ID_0 (*(uint32_t*)0x1fff7a10)
#define U_ID_1 (*(uint32_t*)0x1fff7a14)
#define U_ID_2 (*(uint32_t*)0x1fff7a18)
#define STM32F4
#endif
#ifdef STM32F303xC #ifdef STM32F303xC
#include "stm32f30x_conf.h" #include "stm32f30x_conf.h"
#include "stm32f30x_rcc.h" #include "stm32f30x_rcc.h"

View File

@ -26,6 +26,7 @@ typedef enum {
GYRO_L3GD20, GYRO_L3GD20,
GYRO_MPU6000, GYRO_MPU6000,
GYRO_MPU6500, GYRO_MPU6500,
GYRO_MPU9250,
GYRO_FAKE GYRO_FAKE
} gyroSensor_e; } gyroSensor_e;

View File

@ -45,6 +45,7 @@
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6000.h"
#include "drivers/accgyro_spi_mpu6500.h" #include "drivers/accgyro_spi_mpu6500.h"
#include "drivers/accgyro_spi_mpu9250.h"
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"
#include "drivers/barometer.h" #include "drivers/barometer.h"
@ -267,7 +268,21 @@ bool detectGyro(void)
} }
#endif #endif
; // fallthrough ; // fallthrough
case GYRO_MPU9250:
#ifdef USE_GYRO_SPI_MPU9250
if (mpu9250SpiGyroDetect(&gyro))
{
gyroHardware = GYRO_MPU9250;
#ifdef GYRO_MPU9250_ALIGN
gyroAlign = GYRO_MPU9250_ALIGN;
#endif
break;
}
#endif
; // fallthrough
case GYRO_FAKE: case GYRO_FAKE:
#ifdef USE_FAKE_GYRO #ifdef USE_FAKE_GYRO
if (fakeGyroDetect(&gyro)) { if (fakeGyroDetect(&gyro)) {
@ -632,7 +647,7 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a
memset(&acc, 0, sizeof(acc)); memset(&acc, 0, sizeof(acc));
memset(&gyro, 0, sizeof(gyro)); memset(&gyro, 0, sizeof(gyro));
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) #if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250)
const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); const extiConfig_t *extiConfig = selectMPUIntExtiConfig();