From 4e9923569a6539bdd4491d62d90e44bc120704f8 Mon Sep 17 00:00:00 2001 From: jflyper Date: Sun, 22 Sep 2019 17:55:47 +0900 Subject: [PATCH] NUCLEOF103RG target NUCLEOF103RG is a target for Nucleo-F103RG (Nucleo-F103RB transplanted with STM32F103RG which has 1MB of FLASH). Such hardware with this target comes in handy when a firmware that doesn't fit in smaller FLASH variant when compiled with DEBUG option. The target definition files are straight copy of NAZE, except LED0_PIN has been redefined to use Nucleo's LD2 (User LED). It is also easy to convert exisiting F1 targets to be built to run on the Nucleo-F103RG board: - Add #define FLASH_PAGE_SIZE 0x800 to target.h - Also add #undef USE_DSHOT #undef USE_LED_STRIP #undef USE_TRANSPONDER #undef USE_CAMERA_CONTROL to target.h to avoid non-F1 compatible code from getting in. - Add FLASH_SIZE = 1024 to target.mk --- make/targets_list.mk | 1 + src/link/stm32_flash_f103_1024k.ld | 25 +++ src/main/target/NUCLEOF103RG/README.txt | 21 +++ src/main/target/NUCLEOF103RG/config.c | 79 +++++++++ .../target/NUCLEOF103RG/hardware_revision.c | 123 ++++++++++++++ .../target/NUCLEOF103RG/hardware_revision.h | 37 ++++ src/main/target/NUCLEOF103RG/initialisation.c | 62 +++++++ src/main/target/NUCLEOF103RG/target.c | 45 +++++ src/main/target/NUCLEOF103RG/target.h | 160 ++++++++++++++++++ src/main/target/NUCLEOF103RG/target.mk | 15 ++ 10 files changed, 568 insertions(+) create mode 100644 src/link/stm32_flash_f103_1024k.ld create mode 100644 src/main/target/NUCLEOF103RG/README.txt create mode 100644 src/main/target/NUCLEOF103RG/config.c create mode 100644 src/main/target/NUCLEOF103RG/hardware_revision.c create mode 100644 src/main/target/NUCLEOF103RG/hardware_revision.h create mode 100644 src/main/target/NUCLEOF103RG/initialisation.c create mode 100644 src/main/target/NUCLEOF103RG/target.c create mode 100644 src/main/target/NUCLEOF103RG/target.h create mode 100644 src/main/target/NUCLEOF103RG/target.mk diff --git a/make/targets_list.mk b/make/targets_list.mk index dc3ef076bb..0e69872ec4 100644 --- a/make/targets_list.mk +++ b/make/targets_list.mk @@ -75,6 +75,7 @@ UNSUPPORTED_TARGETS := \ MIDELICF3 \ MOTOLAB \ MULTIFLITEPICO \ + NUCLEOF103RG \ OMNIBUS \ RACEBASE \ RCEXPLORERF3 \ diff --git a/src/link/stm32_flash_f103_1024k.ld b/src/link/stm32_flash_f103_1024k.ld new file mode 100644 index 0000000000..c3149c018a --- /dev/null +++ b/src/link/stm32_flash_f103_1024k.ld @@ -0,0 +1,25 @@ +/* +***************************************************************************** +** +** File : stm32_flash_1m.ld +** +** Abstract : Linker script for STM32F103RG Device with +** 1MByte FLASH, 96KByte RAM +** +***************************************************************************** +*/ + +/* Specify the memory areas. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1020K + FLASH_CONFIG (r) : ORIGIN = 0x0803F000, LENGTH = 4K + + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM) + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/NUCLEOF103RG/README.txt b/src/main/target/NUCLEOF103RG/README.txt new file mode 100644 index 0000000000..41940cc240 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/README.txt @@ -0,0 +1,21 @@ +NUCLEOF103RG is a target for Nucleo-F103RG (Nucleo-F103RB transplanted with STM32F103RG which has 1MB of FLASH). +Such hardware with this target comes in handy when a firmware that doesn't fit in smaller FLASH variant when compiled with DEBUG option must be debugged with a debugger. + +The target definition files are straight copy of NAZE, except LED0_PIN has been redefined to use Nucleo's LD2 (User LED). + +It is also easy to convert exisiting F1 targets to be built to run on the Nucleo-F103RG board: + +- Add + #define FLASH_PAGE_SIZE 0x800 + to target.h + +- Also add +#undef USE_DSHOT +#undef USE_LED_STRIP +#undef USE_TRANSPONDER +#undef USE_CAMERA_CONTROL + to target.h to avoid non-F1 compatible code from getting in. + +- Add +FLASH_SIZE = 1024 + to target.mk diff --git a/src/main/target/NUCLEOF103RG/config.c b/src/main/target/NUCLEOF103RG/config.c new file mode 100644 index 0000000000..4622045de2 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/config.c @@ -0,0 +1,79 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include +#include + +#include "platform.h" + +#ifdef USE_TARGET_CONFIG + +#include "common/axis.h" +#include "common/utils.h" + +#include "drivers/io.h" + +#include "fc/config.h" +#include "fc/rc_controls.h" +#include "fc/controlrate_profile.h" + +#include "flight/failsafe.h" +#include "flight/pid.h" + +#include "pg/rx.h" + +#include "rx/rx.h" + +#include "sensors/acceleration.h" +#include "sensors/compass.h" +#include "sensors/gyro.h" + +#include "pg/beeper_dev.h" +#include "pg/flash.h" +#include "pg/motor.h" + +#include "hardware_revision.h" + +void targetConfiguration(void) +{ + if (hardwareRevision >= NAZE32_REV5) { + // naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN. + beeperDevConfigMutable()->isOpenDrain = false; + beeperDevConfigMutable()->isInverted = true; + } else { + beeperDevConfigMutable()->isOpenDrain = true; + beeperDevConfigMutable()->isInverted = false; + flashConfigMutable()->csTag = IO_TAG_NONE; + } + +#ifdef MAG_INT_EXTI + if (hardwareRevision < NAZE32_REV5) { + compassConfigMutable()->interruptTag = IO_TAG(PB12); + } +#endif +} + +void targetValidateConfiguration(void) +{ + if (hardwareRevision < NAZE32_REV5 && accelerometerConfig()->acc_hardware == ACC_ADXL345) { + accelerometerConfigMutable()->acc_hardware = ACC_NONE; + } +} +#endif diff --git a/src/main/target/NUCLEOF103RG/hardware_revision.c b/src/main/target/NUCLEOF103RG/hardware_revision.c new file mode 100644 index 0000000000..bf52cd0284 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/hardware_revision.c @@ -0,0 +1,123 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "build/build_config.h" + +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_mpu6500.h" +#include "drivers/bus_spi.h" +#include "drivers/io.h" +#include "drivers/time.h" +#include "drivers/system.h" + +#include "hardware_revision.h" + +uint8_t hardwareRevision = UNKNOWN; + +void detectHardwareRevision(void) +{ + if (hse_value == 8000000) + hardwareRevision = NAZE32; + else if (hse_value == 12000000) + hardwareRevision = NAZE32_REV5; +} + +#ifdef USE_SPI + +#define DISABLE_SPI_CS IOHi(nazeSpiCsPin) +#define ENABLE_SPI_CS IOLo(nazeSpiCsPin) + +#define SPI_DEVICE_NONE (0) +#define SPI_DEVICE_FLASH (1) +#define SPI_DEVICE_MPU (2) + +#define M25P16_INSTRUCTION_RDID 0x9F +#define FLASH_M25P16_ID (0x202015) + +static IO_t nazeSpiCsPin = IO_NONE; + +uint8_t detectSpiDevice(void) +{ +#ifdef NAZE_SPI_CS_PIN + nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); +#endif + + const uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; + uint8_t in[4]; + uint32_t flash_id; + + // try autodetect flash chip + delay(50); // short delay required after initialisation of SPI device instance. + ENABLE_SPI_CS; + spiTransfer(NAZE_SPI_INSTANCE, out, in, sizeof(out)); + DISABLE_SPI_CS; + + flash_id = in[1] << 16 | in[2] << 8 | in[3]; + if (flash_id == FLASH_M25P16_ID) + return SPI_DEVICE_FLASH; + + + // try autodetect MPU + delay(50); + ENABLE_SPI_CS; + spiTransferByte(NAZE_SPI_INSTANCE, MPU_RA_WHO_AM_I | MPU6500_BIT_RESET); + in[0] = spiTransferByte(NAZE_SPI_INSTANCE, 0xff); + DISABLE_SPI_CS; + + if (in[0] == MPU6500_WHO_AM_I_CONST) + return SPI_DEVICE_MPU; + + return SPI_DEVICE_NONE; +} + +#endif + +void updateHardwareRevision(void) +{ +#ifdef USE_SPI + uint8_t detectedSpiDevice = detectSpiDevice(); + + if (detectedSpiDevice == SPI_DEVICE_MPU && hardwareRevision == NAZE32_REV5) + hardwareRevision = NAZE32_SP; +#endif +} + +ioTag_t selectMPUIntExtiConfigByHardwareRevision(void) +{ + +#ifdef AFROMINI + return IO_TAG(PC13); +#else + if (hardwareRevision < NAZE32_REV5) { + // MPU_INT output on rev4 PB13 + return IO_TAG(PB13); + } else { + // MPU_INT output on rev5 PC13 + return IO_TAG(PC13); + } +#endif +} diff --git a/src/main/target/NUCLEOF103RG/hardware_revision.h b/src/main/target/NUCLEOF103RG/hardware_revision.h new file mode 100644 index 0000000000..3945398bac --- /dev/null +++ b/src/main/target/NUCLEOF103RG/hardware_revision.h @@ -0,0 +1,37 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +typedef enum nazeHardwareRevision_t { + UNKNOWN = 0, + NAZE32, // Naze32 and compatible with 8MHz HSE + NAZE32_REV5, // Naze32 and compatible with 12MHz HSE + NAZE32_SP // Naze32 w/Sensor Platforms +} nazeHardwareRevision_e; + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); + +void spiBusInit(void); + +ioTag_t selectMPUIntExtiConfigByHardwareRevision(void); diff --git a/src/main/target/NUCLEOF103RG/initialisation.c b/src/main/target/NUCLEOF103RG/initialisation.c new file mode 100644 index 0000000000..57cc3f0c4c --- /dev/null +++ b/src/main/target/NUCLEOF103RG/initialisation.c @@ -0,0 +1,62 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/bus_i2c.h" +#include "drivers/bus_spi.h" + +#include "hardware_revision.h" + +#include "io/serial.h" + +#include "pg/bus_i2c.h" +#include "pg/bus_spi.h" + +#include "sensors/initialisation.h" + +void targetBusInit(void) +{ +#ifdef USE_SPI + spiPinConfigure(spiPinConfig(0)); + sensorsPreInit(); + spiPreinit(); +#ifdef USE_SPI_DEVICE_2 + spiInit(SPIDEV_2); +#endif +#endif + + if (hardwareRevision == NAZE32_SP) { + serialRemovePort(SERIAL_PORT_SOFTSERIAL2); + + if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) { + serialRemovePort(SERIAL_PORT_USART3); + i2cHardwareConfigure(i2cConfig(0)); + i2cInit(I2C_DEVICE); + } + } else { + i2cHardwareConfigure(i2cConfig(0)); + i2cInit(I2C_DEVICE); + } +} diff --git a/src/main/target/NUCLEOF103RG/target.c b/src/main/target/NUCLEOF103RG/target.c new file mode 100644 index 0000000000..df1bbc1594 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/target.c @@ -0,0 +1,45 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#include + +#include "platform.h" +#include "drivers/io.h" + +#include "drivers/timer.h" +#include "drivers/timer_def.h" +#include "drivers/dma.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0), // PWM1 - RC1 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0), // PWM2 - RC2 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0), // PWM3 - RC3 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_PWM, 0), // PWM4 - RC4 + DEF_TIM(TIM3, CH1, PA6, TIM_USE_PWM | TIM_USE_LED, 0), // PWM5 - RC5 + DEF_TIM(TIM3, CH2, PA7, TIM_USE_PWM, 0), // PWM6 - RC6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0), // PWM7 - RC7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0), // PWM8 - RC8 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0), // PWM9 - OUT1 + DEF_TIM(TIM1, CH4, PA11, TIM_USE_MOTOR, 0), // PWM10 - OUT2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0), // PWM11 - OUT3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0), // PWM12 - OUT4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0), // PWM13 - OUT5 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0), // PWM14 - OUT6 +}; diff --git a/src/main/target/NUCLEOF103RG/target.h b/src/main/target/NUCLEOF103RG/target.h new file mode 100644 index 0000000000..8d46b1c856 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/target.h @@ -0,0 +1,160 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +// XL chips has 0x800 page size +#define FLASH_PAGE_SIZE 0x800 + +// Limit some options that are not generally available for F1 targets to avoid non-F1 compatible code to get in +#undef USE_DSHOT +#undef USE_LED_STRIP +#undef USE_TRANSPONDER +#undef USE_CAMERA_CONTROL + +#define TARGET_BOARD_IDENTIFIER "N1RG" + +#define USE_TELEMETRY_IBUS + +#define USE_TARGET_CONFIG +#define TARGET_VALIDATECONFIG +#define USE_HARDWARE_REVISION_DETECTION +#define TARGET_BUS_INIT + +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC + +//#define LED0_PIN PB3 +#define LED0_PIN PA5 +//#define LED1_PIN PB4 + +#define USE_BEEPER +#define BEEPER_PIN PA12 + +//#define BARO_XCLR_PIN PC13 +//#define BARO_EOC_PIN PC14 + +#define INVERTER_PIN_UART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO + +#define USE_RX_MSP + +#define USE_EXTI +#define MAG_INT_EXTI PC14 +#define USE_GYRO_EXTI +#define GYRO_1_EXTI_PIN PC13 +//#define MMA8451_INT_PIN PA5 + +#define USE_MPU_DATA_READY_SIGNAL +#define USE_MAG_DATA_READY_SIGNAL + +#define USE_SPI +#define USE_SPI_DEVICE_2 + +#define NAZE_SPI_INSTANCE SPI2 +#define NAZE_SPI_CS_PIN PB12 + +// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: +#define FLASH_CS_PIN NAZE_SPI_CS_PIN +#define FLASH_SPI_INSTANCE NAZE_SPI_INSTANCE + +#define GYRO_1_CS_PIN NAZE_SPI_CS_PIN +#define GYRO_1_SPI_INSTANCE NAZE_SPI_INSTANCE + +#define USE_FLASHFS +#define USE_FLASH_M25P16 + +#define USE_GYRO +#define USE_FAKE_GYRO +#define USE_GYRO_MPU3050 +#define USE_GYRO_MPU6050 +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 + +#define GYRO_1_ALIGN CW0_DEG + +#define USE_ACC +#define USE_FAKE_ACC +//#define USE_ACC_ADXL345 +//#define USE_ACC_BMA280 +//#define USE_ACC_MMA8452 +#define USE_ACC_MPU6050 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 + +//#define ACC_ADXL345_ALIGN CW270_DEG +//#define ACC_MMA8452_ALIGN CW90_DEG +//#define ACC_BMA280_ALIGN CW0_DEG + +#define USE_BARO +#define USE_BARO_MS5611 // needed for Flip32 board +#define USE_BARO_BMP280 + +/* +#define USE_MAG +#define USE_MAG_HMC5883 +#define MAG_HMC5883_ALIGN CW180_DEG +*/ + +//#define USE_RANGEFINDER +//#define USE_RANGEFINDER_HCSR04 +//#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0 +//#define RANGEFINDER_HCSR04_ECHO_PIN PB1 +//#define RANGEFINDER_HCSR04_TRIGGER_PIN_PWM PB8 +//#define RANGEFINDER_HCSR04_ECHO_PIN_PWM PB9 + +#define USE_UART1 +#define USE_UART2 +/* only 2 uarts available on the NAZE, add ifdef here if present on other boards */ +//#define USE_UART3 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 4 + +#define SOFTSERIAL1_RX_PIN PA6 // PWM 5 +#define SOFTSERIAL1_TX_PIN PA7 // PWM 6 + +#define SOFTSERIAL2_RX_PIN PB0 // PWM 7 +#define SOFTSERIAL2_TX_PIN PB1 // PWM 8 + +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C_DEVICE (I2CDEV_2) + +// #define SOFT_I2C // enable to test software i2c +// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) +// #define SOFT_I2C_PB67 + +#define USE_ADC +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +//#define EXTERNAL1_ADC_PIN PA5 + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM + +// IO - assuming all IOs on 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) ) + +#define USABLE_TIMER_CHANNEL_COUNT 14 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/NUCLEOF103RG/target.mk b/src/main/target/NUCLEOF103RG/target.mk new file mode 100644 index 0000000000..31789f1712 --- /dev/null +++ b/src/main/target/NUCLEOF103RG/target.mk @@ -0,0 +1,15 @@ +F1_TARGETS += $(TARGET) +FEATURES = ONBOARDFLASH +FLASH_SIZE = 1024 + +TARGET_SRC = \ + drivers/accgyro/accgyro_fake.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu3050.c \ + drivers/accgyro/accgyro_mpu6050.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/compass/compass_hmc5883l.c