mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Merge pull request #2434 from blckmn/config_clean
Removed more target specific conditionals from the main codebase
This commit is contained in:
commit
79b4badf62
14 changed files with 65 additions and 122 deletions
|
@ -83,12 +83,10 @@ static uint8_t device_id;
|
||||||
|
|
||||||
static inline void mma8451ConfigureInterrupt(void)
|
static inline void mma8451ConfigureInterrupt(void)
|
||||||
{
|
{
|
||||||
#ifdef NAZE
|
#ifdef MMA8451_INT_PIN
|
||||||
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
|
IOInit(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), OWNER_MPU_EXTI, 0);
|
||||||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
// TODO - maybe pullup / pulldown ?
|
||||||
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
IOConfigGPIO(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), IOCFG_IN_FLOATING);
|
||||||
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU_EXTI, 0);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
|
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
|
||||||
|
|
|
@ -119,11 +119,9 @@
|
||||||
|
|
||||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||||
|
|
||||||
static const hmc5883Config_t *hmc5883Config = NULL;
|
|
||||||
|
|
||||||
#ifdef USE_MAG_DATA_READY_SIGNAL
|
#ifdef USE_MAG_DATA_READY_SIGNAL
|
||||||
|
|
||||||
static IO_t intIO;
|
static IO_t hmc5883InterruptIO;
|
||||||
static extiCallbackRec_t hmc5883_extiCallbackRec;
|
static extiCallbackRec_t hmc5883_extiCallbackRec;
|
||||||
|
|
||||||
static void hmc5883_extiHandler(extiCallbackRec_t* cb)
|
static void hmc5883_extiHandler(extiCallbackRec_t* cb)
|
||||||
|
@ -150,20 +148,19 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_MAG_DATA_READY_SIGNAL
|
#ifdef USE_MAG_DATA_READY_SIGNAL
|
||||||
|
|
||||||
if (!(hmc5883Config->intTag)) {
|
if (!(hmc5883InterruptIO)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
intIO = IOGetByTag(hmc5883Config->intTag);
|
|
||||||
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
|
#ifdef ENSURE_MAG_DATA_READY_IS_HIGH
|
||||||
uint8_t status = IORead(intIO);
|
uint8_t status = IORead(hmc5883InterruptIO);
|
||||||
if (!status) {
|
if (!status) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler);
|
EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler);
|
||||||
EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
|
EXTIConfig(hmc5883InterruptIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
|
||||||
EXTIEnable(intIO, true);
|
EXTIEnable(hmc5883InterruptIO, true);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -257,9 +254,13 @@ static bool hmc5883lInit(void)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
|
bool hmc5883lDetect(magDev_t* mag, ioTag_t interruptTag)
|
||||||
{
|
{
|
||||||
hmc5883Config = hmc5883ConfigToUse;
|
#ifdef USE_MAG_DATA_READY_SIGNAL
|
||||||
|
hmc5883InterruptIO = IOGetByTag(interruptTag);
|
||||||
|
#else
|
||||||
|
UNUSED(interruptTag);
|
||||||
|
#endif
|
||||||
|
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
|
||||||
|
|
|
@ -19,8 +19,4 @@
|
||||||
|
|
||||||
#include "io_types.h"
|
#include "io_types.h"
|
||||||
|
|
||||||
typedef struct hmc5883Config_s {
|
bool hmc5883lDetect(magDev_t* mag, ioTag_t interruptTag);
|
||||||
ioTag_t intTag;
|
|
||||||
} hmc5883Config_t;
|
|
||||||
|
|
||||||
bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse);
|
|
||||||
|
|
|
@ -87,7 +87,7 @@
|
||||||
#define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
#define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
||||||
#define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
#define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN)
|
||||||
|
|
||||||
#if defined(SPRACINGF3NEO)
|
#ifdef RTC6705_POWER_PIN
|
||||||
static IO_t vtxPowerPin = IO_NONE;
|
static IO_t vtxPowerPin = IO_NONE;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -117,6 +117,16 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
accelerometerTrims->values.yaw = 0;
|
accelerometerTrims->values.yaw = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void resetCompassConfig(compassConfig_t* compassConfig)
|
||||||
|
{
|
||||||
|
compassConfig->mag_align = ALIGN_DEFAULT;
|
||||||
|
#ifdef MAG_INT_EXTI
|
||||||
|
compassConfig->interruptTag = IO_TAG(MAG_INT_EXTI);
|
||||||
|
#else
|
||||||
|
compassConfig->interruptTag = IO_TAG_NONE;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
|
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
|
||||||
{
|
{
|
||||||
controlRateConfig->rcRate8 = 100;
|
controlRateConfig->rcRate8 = 100;
|
||||||
|
@ -635,7 +645,8 @@ void createDefaultConfig(master_t *config)
|
||||||
|
|
||||||
config->gyroConfig.gyro_align = ALIGN_DEFAULT;
|
config->gyroConfig.gyro_align = ALIGN_DEFAULT;
|
||||||
config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
|
config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
|
||||||
config->compassConfig.mag_align = ALIGN_DEFAULT;
|
|
||||||
|
resetCompassConfig(&config->compassConfig);
|
||||||
|
|
||||||
config->boardAlignment.rollDegrees = 0;
|
config->boardAlignment.rollDegrees = 0;
|
||||||
config->boardAlignment.pitchDegrees = 0;
|
config->boardAlignment.pitchDegrees = 0;
|
||||||
|
@ -943,12 +954,6 @@ void validateAndFixConfig(void)
|
||||||
featureClear(FEATURE_CURRENT_METER);
|
featureClear(FEATURE_CURRENT_METER);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
|
|
||||||
// led strip needs the same ports
|
|
||||||
featureClear(FEATURE_LED_STRIP);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// software serial needs free PWM ports
|
// software serial needs free PWM ports
|
||||||
featureClear(FEATURE_SOFTSERIAL);
|
featureClear(FEATURE_SOFTSERIAL);
|
||||||
}
|
}
|
||||||
|
@ -968,42 +973,6 @@ void validateAndFixConfig(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(NAZE) && defined(SONAR)
|
|
||||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
|
||||||
featureClear(FEATURE_CURRENT_METER);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(OLIMEXINO) && defined(SONAR)
|
|
||||||
if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
|
||||||
featureClear(FEATURE_CURRENT_METER);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
|
|
||||||
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) {
|
|
||||||
featureClear(FEATURE_DASHBOARD);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
|
|
||||||
// shared pin
|
|
||||||
if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
|
|
||||||
featureClear(FEATURE_SONAR);
|
|
||||||
featureClear(FEATURE_SOFTSERIAL);
|
|
||||||
featureClear(FEATURE_RSSI_ADC);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(COLIBRI_RACE)
|
|
||||||
serialConfig()->portConfigs[0].functionMask = FUNCTION_MSP;
|
|
||||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
|
|
||||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
|
||||||
featureClear(FEATURE_RX_MSP);
|
|
||||||
featureSet(FEATURE_RX_PPM);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
useRxConfig(&masterConfig.rxConfig);
|
useRxConfig(&masterConfig.rxConfig);
|
||||||
|
|
||||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||||
|
|
|
@ -98,11 +98,7 @@ retry:
|
||||||
#ifdef USE_ACC_ADXL345
|
#ifdef USE_ACC_ADXL345
|
||||||
acc_params.useFifo = false;
|
acc_params.useFifo = false;
|
||||||
acc_params.dataRate = 800; // unused currently
|
acc_params.dataRate = 800; // unused currently
|
||||||
#ifdef NAZE
|
|
||||||
if (hardwareRevision < NAZE32_REV5 && adxl345Detect(&acc_params, dev)) {
|
|
||||||
#else
|
|
||||||
if (adxl345Detect(&acc_params, dev)) {
|
if (adxl345Detect(&acc_params, dev)) {
|
||||||
#endif
|
|
||||||
#ifdef ACC_ADXL345_ALIGN
|
#ifdef ACC_ADXL345_ALIGN
|
||||||
dev->accAlign = ACC_ADXL345_ALIGN;
|
dev->accAlign = ACC_ADXL345_ALIGN;
|
||||||
#endif
|
#endif
|
||||||
|
@ -135,12 +131,7 @@ retry:
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
case ACC_MMA8452: // MMA8452
|
case ACC_MMA8452: // MMA8452
|
||||||
#ifdef USE_ACC_MMA8452
|
#ifdef USE_ACC_MMA8452
|
||||||
#ifdef NAZE
|
|
||||||
// Not supported with this frequency
|
|
||||||
if (hardwareRevision < NAZE32_REV5 && mma8452Detect(dev)) {
|
|
||||||
#else
|
|
||||||
if (mma8452Detect(dev)) {
|
if (mma8452Detect(dev)) {
|
||||||
#endif
|
|
||||||
#ifdef ACC_MMA8452_ALIGN
|
#ifdef ACC_MMA8452_ALIGN
|
||||||
dev->accAlign = ACC_MMA8452_ALIGN;
|
dev->accAlign = ACC_MMA8452_ALIGN;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -71,12 +71,6 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
||||||
bmp085Config = &defaultBMP085Config;
|
bmp085Config = &defaultBMP085Config;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef NAZE
|
|
||||||
if (hardwareRevision == NAZE32) {
|
|
||||||
bmp085Disable(bmp085Config);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
switch (baroHardware) {
|
switch (baroHardware) {
|
||||||
|
|
|
@ -56,33 +56,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
||||||
{
|
{
|
||||||
magSensor_e magHardware;
|
magSensor_e magHardware;
|
||||||
|
|
||||||
#ifdef USE_MAG_HMC5883
|
|
||||||
const hmc5883Config_t *hmc5883Config = 0;
|
|
||||||
|
|
||||||
#ifdef NAZE // TODO remove this target specific define
|
|
||||||
static const hmc5883Config_t nazeHmc5883Config_v1_v4 = {
|
|
||||||
.intTag = IO_TAG(PB12) /* perhaps disabled? */
|
|
||||||
};
|
|
||||||
static const hmc5883Config_t nazeHmc5883Config_v5 = {
|
|
||||||
.intTag = IO_TAG(MAG_INT_EXTI)
|
|
||||||
};
|
|
||||||
if (hardwareRevision < NAZE32_REV5) {
|
|
||||||
hmc5883Config = &nazeHmc5883Config_v1_v4;
|
|
||||||
} else {
|
|
||||||
hmc5883Config = &nazeHmc5883Config_v5;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef MAG_INT_EXTI
|
|
||||||
static const hmc5883Config_t extiHmc5883Config = {
|
|
||||||
.intTag = IO_TAG(MAG_INT_EXTI)
|
|
||||||
};
|
|
||||||
|
|
||||||
hmc5883Config = &extiHmc5883Config;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
retry:
|
retry:
|
||||||
|
|
||||||
dev->magAlign = ALIGN_DEFAULT;
|
dev->magAlign = ALIGN_DEFAULT;
|
||||||
|
@ -93,7 +66,7 @@ retry:
|
||||||
|
|
||||||
case MAG_HMC5883:
|
case MAG_HMC5883:
|
||||||
#ifdef USE_MAG_HMC5883
|
#ifdef USE_MAG_HMC5883
|
||||||
if (hmc5883lDetect(dev, hmc5883Config)) {
|
if (hmc5883lDetect(dev, compassConfig()->interruptTag)) {
|
||||||
#ifdef MAG_HMC5883_ALIGN
|
#ifdef MAG_HMC5883_ALIGN
|
||||||
dev->magAlign = MAG_HMC5883_ALIGN;
|
dev->magAlign = MAG_HMC5883_ALIGN;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -18,10 +18,11 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
|
|
||||||
// Type of magnetometer used/detected
|
// Type of magnetometer used/detected
|
||||||
typedef enum {
|
typedef enum {
|
||||||
MAG_DEFAULT = 0,
|
MAG_DEFAULT = 0,
|
||||||
|
@ -43,6 +44,7 @@ typedef struct compassConfig_s {
|
||||||
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||||
sensor_align_e mag_align; // mag alignment
|
sensor_align_e mag_align; // mag alignment
|
||||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||||
|
ioTag_t interruptTag;
|
||||||
flightDynamicsTrims_t magZero;
|
flightDynamicsTrims_t magZero;
|
||||||
} compassConfig_t;
|
} compassConfig_t;
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
@ -99,3 +100,15 @@ void targetConfiguration(master_t *config)
|
||||||
targetApplyDefaultLedStripConfig(config->ledStripConfig.ledConfigs);
|
targetApplyDefaultLedStripConfig(config->ledStripConfig.ledConfigs);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void targetValidateConfiguration(master_t *config)
|
||||||
|
{
|
||||||
|
UNUSED(config);
|
||||||
|
|
||||||
|
serialConfig()->portConfigs[0].functionMask = FUNCTION_MSP;
|
||||||
|
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
|
||||||
|
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||||
|
featureClear(FEATURE_RX_MSP);
|
||||||
|
featureSet(FEATURE_RX_PPM);
|
||||||
|
}
|
||||||
|
}
|
|
@ -70,10 +70,6 @@
|
||||||
#include "config/config_master.h"
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
|
||||||
#ifdef NAZE
|
|
||||||
#include "hardware_revision.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "bus_bst.h"
|
#include "bus_bst.h"
|
||||||
#include "i2c_bst.h"
|
#include "i2c_bst.h"
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#define BST_DEVICE_NAME "COLIBRI RACE"
|
#define BST_DEVICE_NAME "COLIBRI RACE"
|
||||||
#define BST_DEVICE_NAME_LENGTH 12
|
#define BST_DEVICE_NAME_LENGTH 12
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
#define TARGET_VALIDATECONFIG
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||||
|
|
||||||
|
|
|
@ -96,5 +96,19 @@ void targetConfiguration(master_t *config)
|
||||||
config->flashConfig.csTag = IO_TAG_NONE;
|
config->flashConfig.csTag = IO_TAG_NONE;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef MAG_INT_EXTI
|
||||||
|
if (hardwareRevision < NAZE32_REV5) {
|
||||||
|
config->compassConfig.interruptTag = IO_TAG(PB12);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void targetValidateConfiguration(master_t *config)
|
||||||
|
{
|
||||||
|
UNUSED(config);
|
||||||
|
|
||||||
|
if (hardwareRevision < NAZE32_REV5 && config->accelerometerConfig.acc_hardware == ACC_ADXL345) {
|
||||||
|
config->accelerometerConfig.acc_hardware = ACC_NONE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define TARGET_CONFIG
|
#define TARGET_CONFIG
|
||||||
|
#define TARGET_VALIDATECONFIG
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
#define TARGET_BUS_INIT
|
#define TARGET_BUS_INIT
|
||||||
|
|
||||||
|
@ -49,16 +50,10 @@
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define MAG_INT_EXTI PC14
|
#define MAG_INT_EXTI PC14
|
||||||
#define MPU_INT_EXTI PC13
|
#define MPU_INT_EXTI PC13
|
||||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
#define MMA8451_INT_PIN PA5
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
|
||||||
//#define DEBUG_MAG_DATA_READY_INTERRUPT
|
|
||||||
#define USE_MAG_DATA_READY_SIGNAL
|
|
||||||
|
|
||||||
// SPI2
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
// PB15 28 SPI2_MOSI
|
#define USE_MAG_DATA_READY_SIGNAL
|
||||||
// PB14 27 SPI2_MISO
|
|
||||||
// PB13 26 SPI2_SCK
|
|
||||||
// PB12 25 SPI2_NSS
|
|
||||||
|
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue