mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
new SPI2 driver w/testcase
5883 and 6050 driver updates git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@363 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
57cbd784a9
commit
3b8c1841f8
8 changed files with 2158 additions and 1974 deletions
|
@ -642,6 +642,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -813,6 +818,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\printf.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>stm32f10x_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
</Groups>
|
||||
|
@ -1453,6 +1463,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1568,6 +1583,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\printf.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>stm32f10x_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
</Groups>
|
||||
|
@ -2448,6 +2468,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -2619,6 +2644,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\printf.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>stm32f10x_spi.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
</Groups>
|
||||
|
|
3973
obj/baseflight.hex
3973
obj/baseflight.hex
File diff suppressed because it is too large
Load diff
|
@ -206,6 +206,7 @@ typedef struct baro_t
|
|||
#include "drv_ms5611.h"
|
||||
#include "drv_hmc5883l.h"
|
||||
#include "drv_i2c.h"
|
||||
#include "drv_spi.h"
|
||||
#include "drv_ledring.h"
|
||||
#include "drv_mma845x.h"
|
||||
#include "drv_mpu3050.h"
|
||||
|
|
|
@ -42,11 +42,17 @@ void hmc5883lInit(float *calibrationGain)
|
|||
int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow.
|
||||
bool bret = true; // Error indicator
|
||||
|
||||
if (hse_value == 8000000) {
|
||||
// PB12 - MAG_DRDY output on rev4 hardware
|
||||
gpio.pin = Pin_12;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
} else if (hse_value == 12000000) {
|
||||
// PC14 - MAG_DRDY output on rev5 hardware
|
||||
gpio.pin = Pin_14;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
}
|
||||
|
||||
delay(50);
|
||||
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
||||
|
|
|
@ -268,11 +268,14 @@ static void mpu6050GyroInit(void)
|
|||
{
|
||||
gpio_config_t gpio;
|
||||
|
||||
// PB13 - MPU_INT output on rev4 hardware
|
||||
// MPU_INT output on rev4/5 hardware (PB13, PC13)
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
if (hse_value == 8000000)
|
||||
gpioInit(GPIOB, &gpio);
|
||||
else if (hse_value == 12000000)
|
||||
gpioInit(GPIOC, &gpio);
|
||||
|
||||
#ifndef MPU6050_DMP
|
||||
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||
|
|
101
src/drv_spi.c
Normal file
101
src/drv_spi.c
Normal file
|
@ -0,0 +1,101 @@
|
|||
#include "board.h"
|
||||
|
||||
// SPI2 Driver
|
||||
// PB15 28 SPI2_MOSI
|
||||
// PB14 27 SPI2_MISO
|
||||
// PB13 26 SPI2_SCK
|
||||
// PB12 25 SPI2_NSS
|
||||
|
||||
static bool spiTest(void);
|
||||
|
||||
bool spiInit(void)
|
||||
{
|
||||
gpio_config_t gpio;
|
||||
SPI_InitTypeDef spi;
|
||||
|
||||
// Enable SPI2 clock
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
|
||||
|
||||
// MOSI + SCK as output
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpio.pin = Pin_13 | Pin_15;
|
||||
gpio.speed = Speed_50MHz;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
// MISO as input
|
||||
gpio.pin = Pin_14;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
// NSS as gpio slave select
|
||||
gpio.pin = Pin_12;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
// Init SPI2 hardware
|
||||
SPI_I2S_DeInit(SPI2);
|
||||
spi.SPI_Mode = SPI_Mode_Master;
|
||||
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
|
||||
spi.SPI_DataSize = SPI_DataSize_8b;
|
||||
spi.SPI_NSS = SPI_NSS_Soft;
|
||||
spi.SPI_FirstBit = SPI_FirstBit_MSB;
|
||||
spi.SPI_CRCPolynomial = 7;
|
||||
spi.SPI_CPOL = SPI_CPOL_High;
|
||||
spi.SPI_CPHA = SPI_CPHA_2Edge;
|
||||
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
|
||||
SPI_Init(SPI2, &spi);
|
||||
SPI_Cmd(SPI2, ENABLE);
|
||||
|
||||
return spiTest();
|
||||
}
|
||||
|
||||
void spiSelect(bool select)
|
||||
{
|
||||
if (select) {
|
||||
digitalLo(GPIOB, Pin_12);
|
||||
} else {
|
||||
digitalHi(GPIOB, Pin_12);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t spiTransferByte(uint8_t in)
|
||||
{
|
||||
uint8_t rx;
|
||||
SPI2->DR;
|
||||
SPI2->DR = in;
|
||||
while (!(SPI2->SR & SPI_I2S_FLAG_RXNE));
|
||||
rx = SPI2->DR;
|
||||
while (!(SPI2->SR & SPI_I2S_FLAG_TXE));
|
||||
while (SPI2->SR & SPI_I2S_FLAG_BSY);
|
||||
return rx;
|
||||
}
|
||||
|
||||
bool spiTransfer(uint8_t *out, uint8_t *in, int len)
|
||||
{
|
||||
uint8_t b;
|
||||
SPI2->DR;
|
||||
while (len--) {
|
||||
b = in ? *(in++) : 0xFF;
|
||||
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_TXE) == RESET);
|
||||
SPI_I2S_SendData(SPI2, b);
|
||||
while (SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_RXNE) == RESET);
|
||||
b = SPI_I2S_ReceiveData(SPI2);
|
||||
if (out)
|
||||
*(out++) = b;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool spiTest(void)
|
||||
{
|
||||
uint8_t out[] = { 0x9F, 0, 0, 0 };
|
||||
uint8_t in[4];
|
||||
|
||||
spiSelect(true);
|
||||
spiTransfer(in, out, sizeof(out));
|
||||
spiSelect(false);
|
||||
if (in[1] == 0xEF)
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
3
src/drv_spi.h
Normal file
3
src/drv_spi.h
Normal file
|
@ -0,0 +1,3 @@
|
|||
#pragma once
|
||||
|
||||
bool spiInit(void);
|
|
@ -101,6 +101,7 @@ void systemInit(void)
|
|||
#ifndef FY90Q
|
||||
i2cInit(I2C2);
|
||||
#endif
|
||||
spiInit();
|
||||
|
||||
// sleep for 100ms
|
||||
delay(100);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue