Merge pull request #626 from blckmn/development
Update hmc5883l to use new IO
This commit is contained in:
commit
0d3b65071e
|
@ -26,7 +26,7 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "gpio.h"
|
#include "io.h"
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
|
|
||||||
#include "sensor.h"
|
#include "sensor.h"
|
||||||
|
|
|
@ -22,8 +22,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* LSM303DLHC ACC struct */
|
/* LSM303DLHC ACC struct */
|
||||||
typedef struct
|
typedef struct {
|
||||||
{
|
|
||||||
uint8_t Power_Mode; /* Power-down/Normal Mode */
|
uint8_t Power_Mode; /* Power-down/Normal Mode */
|
||||||
uint8_t AccOutput_DataRate; /* OUT data rate */
|
uint8_t AccOutput_DataRate; /* OUT data rate */
|
||||||
uint8_t Axes_Enable; /* Axes enable */
|
uint8_t Axes_Enable; /* Axes enable */
|
||||||
|
@ -31,25 +30,23 @@ typedef struct
|
||||||
uint8_t BlockData_Update; /* Block Data Update */
|
uint8_t BlockData_Update; /* Block Data Update */
|
||||||
uint8_t Endianness; /* Endian Data selection */
|
uint8_t Endianness; /* Endian Data selection */
|
||||||
uint8_t AccFull_Scale; /* Full Scale selection */
|
uint8_t AccFull_Scale; /* Full Scale selection */
|
||||||
}LSM303DLHCAcc_InitTypeDef;
|
} LSM303DLHCAcc_InitTypeDef;
|
||||||
|
|
||||||
/* LSM303DLHC Acc High Pass Filter struct */
|
/* LSM303DLHC Acc High Pass Filter struct */
|
||||||
typedef struct
|
typedef struct {
|
||||||
{
|
|
||||||
uint8_t HighPassFilter_Mode_Selection; /* Internal filter mode */
|
uint8_t HighPassFilter_Mode_Selection; /* Internal filter mode */
|
||||||
uint8_t HighPassFilter_CutOff_Frequency; /* High pass filter cut-off frequency */
|
uint8_t HighPassFilter_CutOff_Frequency; /* High pass filter cut-off frequency */
|
||||||
uint8_t HighPassFilter_AOI1; /* HPF_enabling/disabling for AOI function on interrupt 1 */
|
uint8_t HighPassFilter_AOI1; /* HPF_enabling/disabling for AOI function on interrupt 1 */
|
||||||
uint8_t HighPassFilter_AOI2; /* HPF_enabling/disabling for AOI function on interrupt 2 */
|
uint8_t HighPassFilter_AOI2; /* HPF_enabling/disabling for AOI function on interrupt 2 */
|
||||||
}LSM303DLHCAcc_FilterConfigTypeDef;
|
} LSM303DLHCAcc_FilterConfigTypeDef;
|
||||||
|
|
||||||
/* LSM303DLHC Mag struct */
|
/* LSM303DLHC Mag struct */
|
||||||
typedef struct
|
typedef struct {
|
||||||
{
|
|
||||||
uint8_t Temperature_Sensor; /* Temperature sensor enable/disable */
|
uint8_t Temperature_Sensor; /* Temperature sensor enable/disable */
|
||||||
uint8_t MagOutput_DataRate; /* OUT data rate */
|
uint8_t MagOutput_DataRate; /* OUT data rate */
|
||||||
uint8_t Working_Mode; /* operating mode */
|
uint8_t Working_Mode; /* operating mode */
|
||||||
uint8_t MagFull_Scale; /* Full Scale selection */
|
uint8_t MagFull_Scale; /* Full Scale selection */
|
||||||
}LSM303DLHCMag_InitTypeDef;
|
} LSM303DLHCMag_InitTypeDef;
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
*/
|
*/
|
||||||
|
@ -78,43 +75,11 @@ typedef struct
|
||||||
* @brief LSM303DLHC I2C Interface pins
|
* @brief LSM303DLHC I2C Interface pins
|
||||||
*/
|
*/
|
||||||
#define LSM303DLHC_I2C I2C1
|
#define LSM303DLHC_I2C I2C1
|
||||||
#define LSM303DLHC_I2C_CLK RCC_APB1Periph_I2C1
|
#define LSM303DLHC_I2C_SCK_PIN PB6 /* PB.06 */
|
||||||
|
#define LSM303DLHC_I2C_SDA_PIN PB7 /* PB.7 */
|
||||||
#define LSM303DLHC_I2C_SCK_PIN GPIO_Pin_6 /* PB.06 */
|
#define LSM303DLHC_DRDY_PIN PE2 /* PE.02 */
|
||||||
#define LSM303DLHC_I2C_SCK_GPIO_PORT GPIOB /* GPIOB */
|
#define LSM303DLHC_I2C_INT1_PIN PE4 /* PE.04 */
|
||||||
#define LSM303DLHC_I2C_SCK_GPIO_CLK RCC_AHBPeriph_GPIOB
|
#define LSM303DLHC_I2C_INT2_PIN PE5 /* PE.05 */
|
||||||
#define LSM303DLHC_I2C_SCK_SOURCE GPIO_PinSource6
|
|
||||||
#define LSM303DLHC_I2C_SCK_AF GPIO_AF_4
|
|
||||||
|
|
||||||
#define LSM303DLHC_I2C_SDA_PIN GPIO_Pin_7 /* PB.7 */
|
|
||||||
#define LSM303DLHC_I2C_SDA_GPIO_PORT GPIOB /* GPIOB */
|
|
||||||
#define LSM303DLHC_I2C_SDA_GPIO_CLK RCC_AHBPeriph_GPIOB
|
|
||||||
#define LSM303DLHC_I2C_SDA_SOURCE GPIO_PinSource7
|
|
||||||
#define LSM303DLHC_I2C_SDA_AF GPIO_AF_4
|
|
||||||
|
|
||||||
#define LSM303DLHC_DRDY_PIN GPIO_Pin_2 /* PE.02 */
|
|
||||||
#define LSM303DLHC_DRDY_GPIO_PORT GPIOE /* GPIOE */
|
|
||||||
#define LSM303DLHC_DRDY_GPIO_CLK RCC_AHBPeriph_GPIOE
|
|
||||||
#define LSM303DLHC_DRDY_EXTI_LINE EXTI_Line2
|
|
||||||
#define LSM303DLHC_DRDY_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
|
|
||||||
#define LSM303DLHC_DRDY_EXTI_PIN_SOURCE EXTI_PinSource2
|
|
||||||
#define LSM303DLHC_DRDY_EXTI_IRQn EXTI2_TS_IRQn
|
|
||||||
|
|
||||||
#define LSM303DLHC_I2C_INT1_PIN GPIO_Pin_4 /* PE.04 */
|
|
||||||
#define LSM303DLHC_I2C_INT1_GPIO_PORT GPIOE /* GPIOE */
|
|
||||||
#define LSM303DLHC_I2C_INT1_GPIO_CLK RCC_AHBPeriph_GPIOE
|
|
||||||
#define LSM303DLHC_I2C_INT1_EXTI_LINE EXTI_Line4
|
|
||||||
#define LSM303DLHC_I2C_INT1_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
|
|
||||||
#define LSM303DLHC_I2C_INT1_EXTI_PIN_SOURCE EXTI_PinSource4
|
|
||||||
#define LSM303DLHC_I2C_INT1_EXTI_IRQn EXTI4_IRQn
|
|
||||||
|
|
||||||
#define LSM303DLHC_I2C_INT2_PIN GPIO_Pin_5 /* PE.05 */
|
|
||||||
#define LSM303DLHC_I2C_INT2_GPIO_PORT GPIOE /* GPIOE */
|
|
||||||
#define LSM303DLHC_I2C_INT2_GPIO_CLK RCC_AHBPeriph_GPIOE
|
|
||||||
#define LSM303DLHC_I2C_INT2_EXTI_LINE EXTI_Line5
|
|
||||||
#define LSM303DLHC_I2C_INT2_EXTI_PORT_SOURCE EXTI_PortSourceGPIOE
|
|
||||||
#define LSM303DLHC_I2C_INT2_EXTI_PIN_SOURCE EXTI_PinSource5ss
|
|
||||||
#define LSM303DLHC_I2C_INT2_EXTI_IRQn EXTI9_5_IRQn
|
|
||||||
|
|
||||||
/******************************************************************************/
|
/******************************************************************************/
|
||||||
/*************************** START REGISTER MAPPING **************************/
|
/*************************** START REGISTER MAPPING **************************/
|
||||||
|
|
|
@ -17,6 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "exti.h"
|
||||||
|
|
||||||
// MPU6050
|
// MPU6050
|
||||||
#define MPU_RA_WHO_AM_I 0x75
|
#define MPU_RA_WHO_AM_I 0x75
|
||||||
#define MPU_RA_WHO_AM_I_LEGACY 0x00
|
#define MPU_RA_WHO_AM_I_LEGACY 0x00
|
||||||
|
|
|
@ -31,6 +31,15 @@
|
||||||
|
|
||||||
#ifndef SOFT_I2C
|
#ifndef SOFT_I2C
|
||||||
|
|
||||||
|
#if defined(USE_I2C_PULLUP)
|
||||||
|
#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
|
||||||
|
#else
|
||||||
|
#define IOCFG_I2C IOCFG_AF_OD
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define I2C_HIGHSPEED_TIMING 0x00500E30 // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
||||||
|
#define I2C_STANDARD_TIMING 0x00E0257A // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||||
|
|
||||||
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
|
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
|
||||||
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
|
||||||
#define I2C_GPIO_AF GPIO_AF_4
|
#define I2C_GPIO_AF GPIO_AF_4
|
||||||
|
@ -83,8 +92,8 @@ void i2cInit(I2CDevice device)
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||||
|
|
||||||
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4);
|
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
||||||
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_UP), GPIO_AF_4);
|
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
||||||
|
|
||||||
I2C_InitTypeDef i2cInit = {
|
I2C_InitTypeDef i2cInit = {
|
||||||
.I2C_Mode = I2C_Mode_I2C,
|
.I2C_Mode = I2C_Mode_I2C,
|
||||||
|
@ -93,10 +102,7 @@ void i2cInit(I2CDevice device)
|
||||||
.I2C_OwnAddress1 = 0x00,
|
.I2C_OwnAddress1 = 0x00,
|
||||||
.I2C_Ack = I2C_Ack_Enable,
|
.I2C_Ack = I2C_Ack_Enable,
|
||||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||||
.I2C_Timing = i2c->overClock ?
|
.I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING)
|
||||||
0x00500E30 : // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
|
|
||||||
0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
|
||||||
//.I2C_Timing = 0x8000050B;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
I2C_Init(I2Cx, &i2cInit);
|
I2C_Init(I2Cx, &i2cInit);
|
||||||
|
|
|
@ -30,8 +30,6 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "gpio.h"
|
|
||||||
#include "exti.h"
|
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
#include "bus_spi.h"
|
#include "bus_spi.h"
|
||||||
|
|
||||||
|
|
|
@ -29,7 +29,8 @@
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "nvic.h"
|
#include "nvic.h"
|
||||||
#include "gpio.h"
|
#include "io.h"
|
||||||
|
#include "exti.h"
|
||||||
#include "bus_i2c.h"
|
#include "bus_i2c.h"
|
||||||
#include "light_led.h"
|
#include "light_led.h"
|
||||||
|
|
||||||
|
@ -120,14 +121,14 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||||
|
|
||||||
static const hmc5883Config_t *hmc5883Config = NULL;
|
static const hmc5883Config_t *hmc5883Config = NULL;
|
||||||
|
|
||||||
void MAG_DATA_READY_EXTI_Handler(void)
|
#ifdef USE_MAG_DATA_READY_SIGNAL
|
||||||
|
|
||||||
|
static IO_t intIO;
|
||||||
|
static extiCallbackRec_t hmc5883_extiCallbackRec;
|
||||||
|
|
||||||
|
void hmc5883_extiHandler(extiCallbackRec_t* cb)
|
||||||
{
|
{
|
||||||
if (EXTI_GetITStatus(hmc5883Config->exti_line) == RESET) {
|
UNUSED(cb);
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
|
|
||||||
|
|
||||||
#ifdef DEBUG_MAG_DATA_READY_INTERRUPT
|
#ifdef DEBUG_MAG_DATA_READY_INTERRUPT
|
||||||
// Measure the delta between calls to the interrupt handler
|
// Measure the delta between calls to the interrupt handler
|
||||||
// currently should be around 65/66 milli seconds / 15hz output rate
|
// currently should be around 65/66 milli seconds / 15hz output rate
|
||||||
|
@ -143,57 +144,26 @@ void MAG_DATA_READY_EXTI_Handler(void)
|
||||||
lastCalledAt = now;
|
lastCalledAt = now;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static void hmc5883lConfigureDataReadyInterruptHandling(void)
|
static void hmc5883lConfigureDataReadyInterruptHandling(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_MAG_DATA_READY_SIGNAL
|
#ifdef USE_MAG_DATA_READY_SIGNAL
|
||||||
|
|
||||||
if (!(hmc5883Config->exti_port_source && hmc5883Config->exti_pin_source)) {
|
if (!(hmc5883Config->intTag)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#ifdef STM32F10X
|
intIO = IOGetByTag(hmc5883Config->intTag);
|
||||||
// enable AFIO for EXTI support
|
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
|
||||||
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
|
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef STM32F10X
|
|
||||||
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
|
||||||
gpioExtiLineConfig(hmc5883Config->exti_port_source, hmc5883Config->exti_pin_source);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
|
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
uint8_t status = GPIO_ReadInputDataBit(hmc5883Config->gpioPort, hmc5883Config->gpioPin);
|
uint8_t status = IORead(intIO);
|
||||||
if (!status) {
|
if (!status) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
registerExtiCallbackHandler(hmc5883Config->exti_irqn, MAG_DATA_READY_EXTI_Handler);
|
EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler);
|
||||||
|
EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
|
||||||
EXTI_ClearITPendingBit(hmc5883Config->exti_line);
|
EXTIEnable(intIO, true);
|
||||||
|
|
||||||
EXTI_InitTypeDef EXTIInit;
|
|
||||||
EXTIInit.EXTI_Line = hmc5883Config->exti_line;
|
|
||||||
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
|
|
||||||
EXTIInit.EXTI_Trigger = EXTI_Trigger_Falling;
|
|
||||||
EXTIInit.EXTI_LineCmd = ENABLE;
|
|
||||||
EXTI_Init(&EXTIInit);
|
|
||||||
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = hmc5883Config->exti_irqn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MAG_DATA_READY);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MAG_DATA_READY);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -221,25 +191,6 @@ void hmc5883lInit(void)
|
||||||
int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow.
|
int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow.
|
||||||
bool bret = true; // Error indicator
|
bool bret = true; // Error indicator
|
||||||
|
|
||||||
gpio_config_t gpio;
|
|
||||||
|
|
||||||
if (hmc5883Config) {
|
|
||||||
#ifdef STM32F303
|
|
||||||
if (hmc5883Config->gpioAHBPeripherals) {
|
|
||||||
RCC_AHBPeriphClockCmd(hmc5883Config->gpioAHBPeripherals, ENABLE);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#ifdef STM32F10X
|
|
||||||
if (hmc5883Config->gpioAPB2Peripherals) {
|
|
||||||
RCC_APB2PeriphClockCmd(hmc5883Config->gpioAPB2Peripherals, ENABLE);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
gpio.pin = hmc5883Config->gpioPin;
|
|
||||||
gpio.speed = Speed_2MHz;
|
|
||||||
gpio.mode = Mode_IN_FLOATING;
|
|
||||||
gpioInit(hmc5883Config->gpioPort, &gpio);
|
|
||||||
}
|
|
||||||
|
|
||||||
delay(50);
|
delay(50);
|
||||||
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
||||||
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
|
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
|
||||||
|
|
|
@ -17,20 +17,10 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
typedef struct hmc5883Config_s {
|
#include "io.h"
|
||||||
#ifdef STM32F303
|
|
||||||
uint32_t gpioAHBPeripherals;
|
|
||||||
#endif
|
|
||||||
#ifdef STM32F10X
|
|
||||||
uint32_t gpioAPB2Peripherals;
|
|
||||||
#endif
|
|
||||||
uint16_t gpioPin;
|
|
||||||
GPIO_TypeDef *gpioPort;
|
|
||||||
|
|
||||||
uint8_t exti_port_source;
|
typedef struct hmc5883Config_s {
|
||||||
uint32_t exti_line;
|
ioTag_t intTag;
|
||||||
uint8_t exti_pin_source;
|
|
||||||
IRQn_Type exti_irqn;
|
|
||||||
} hmc5883Config_t;
|
} hmc5883Config_t;
|
||||||
|
|
||||||
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);
|
bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
#ifdef NAZE
|
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||||
#include "hardware_revision.h"
|
#include "hardware_revision.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -484,27 +484,12 @@ static void detectMag(magSensor_e magHardwareToUse)
|
||||||
#ifdef USE_MAG_HMC5883
|
#ifdef USE_MAG_HMC5883
|
||||||
const hmc5883Config_t *hmc5883Config = 0;
|
const hmc5883Config_t *hmc5883Config = 0;
|
||||||
|
|
||||||
#ifdef NAZE
|
#ifdef NAZE // TODO remove this target specific define
|
||||||
static const hmc5883Config_t nazeHmc5883Config_v1_v4 = {
|
static const hmc5883Config_t nazeHmc5883Config_v1_v4 = {
|
||||||
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
|
.intTag = IO_TAG(PB12) /* perhaps disabled? */
|
||||||
.gpioPin = Pin_12,
|
|
||||||
.gpioPort = GPIOB,
|
|
||||||
|
|
||||||
/* Disabled for v4 needs more work.
|
|
||||||
.exti_port_source = GPIO_PortSourceGPIOB,
|
|
||||||
.exti_pin_source = GPIO_PinSource12,
|
|
||||||
.exti_line = EXTI_Line12,
|
|
||||||
.exti_irqn = EXTI15_10_IRQn
|
|
||||||
*/
|
|
||||||
};
|
};
|
||||||
static const hmc5883Config_t nazeHmc5883Config_v5 = {
|
static const hmc5883Config_t nazeHmc5883Config_v5 = {
|
||||||
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
|
.intTag = IO_TAG(MAG_INT_EXTI)
|
||||||
.gpioPin = Pin_14,
|
|
||||||
.gpioPort = GPIOC,
|
|
||||||
.exti_port_source = GPIO_PortSourceGPIOC,
|
|
||||||
.exti_line = EXTI_Line14,
|
|
||||||
.exti_pin_source = GPIO_PinSource14,
|
|
||||||
.exti_irqn = EXTI15_10_IRQn
|
|
||||||
};
|
};
|
||||||
if (hardwareRevision < NAZE32_REV5) {
|
if (hardwareRevision < NAZE32_REV5) {
|
||||||
hmc5883Config = &nazeHmc5883Config_v1_v4;
|
hmc5883Config = &nazeHmc5883Config_v1_v4;
|
||||||
|
@ -513,18 +498,12 @@ static void detectMag(magSensor_e magHardwareToUse)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SPRACINGF3
|
#ifdef MAG_INT_EXTI
|
||||||
static const hmc5883Config_t spRacingF3Hmc5883Config = {
|
static const hmc5883Config_t extiHmc5883Config = {
|
||||||
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
|
.intTag = IO_TAG(MAG_INT_EXTI)
|
||||||
.gpioPin = Pin_14,
|
|
||||||
.gpioPort = GPIOC,
|
|
||||||
.exti_port_source = EXTI_PortSourceGPIOC,
|
|
||||||
.exti_pin_source = EXTI_PinSource14,
|
|
||||||
.exti_line = EXTI_Line14,
|
|
||||||
.exti_irqn = EXTI15_10_IRQn
|
|
||||||
};
|
};
|
||||||
|
|
||||||
hmc5883Config = &spRacingF3Hmc5883Config;
|
hmc5883Config = &extiHmc5883Config;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -74,7 +74,8 @@
|
||||||
|
|
||||||
//#define DEBUG_MAG_DATA_READY_INTERRUPT
|
//#define DEBUG_MAG_DATA_READY_INTERRUPT
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
|
#define MAG_INT_EXTI PC14
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_MPU3050
|
#define USE_GYRO_MPU3050
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
|
|
|
@ -35,10 +35,6 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
|
||||||
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
|
||||||
|
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_MPU6050
|
#define USE_GYRO_MPU6050
|
||||||
#define GYRO_MPU6050_ALIGN CW270_DEG
|
#define GYRO_MPU6050_ALIGN CW270_DEG
|
||||||
|
@ -57,6 +53,11 @@
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
#define MAG_HMC5883_ALIGN CW270_DEG
|
#define MAG_HMC5883_ALIGN CW270_DEG
|
||||||
|
|
||||||
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
|
#define ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
|
#define MAG_INT_EXTI PC14
|
||||||
|
|
||||||
|
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue