From 49a4d514be2b90f51ce180becbce0e93cb93eba8 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Sun, 16 Sep 2018 22:52:20 +0200 Subject: [PATCH] Add KAKUTEF7 target --- src/main/drivers/accgyro/accgyro_icm20689.c | 149 ++++++++++++++++++ src/main/drivers/accgyro/accgyro_icm20689.h | 32 ++++ src/main/drivers/bus.h | 1 + src/main/drivers/serial_uart.c | 2 +- src/main/fc/cli.c | 2 +- src/main/fc/settings.yaml | 2 +- src/main/sensors/acceleration.c | 18 +++ src/main/sensors/acceleration.h | 3 +- src/main/sensors/gyro.c | 13 ++ src/main/sensors/gyro.h | 1 + src/main/target/KAKUTEF7/target.c | 46 ++++++ src/main/target/KAKUTEF7/target.h | 160 ++++++++++++++++++++ src/main/target/KAKUTEF7/target.mk | 16 ++ 13 files changed, 441 insertions(+), 4 deletions(-) create mode 100644 src/main/drivers/accgyro/accgyro_icm20689.c create mode 100644 src/main/drivers/accgyro/accgyro_icm20689.h create mode 100755 src/main/target/KAKUTEF7/target.c create mode 100644 src/main/target/KAKUTEF7/target.h create mode 100755 src/main/target/KAKUTEF7/target.mk diff --git a/src/main/drivers/accgyro/accgyro_icm20689.c b/src/main/drivers/accgyro/accgyro_icm20689.c new file mode 100644 index 00000000000..4766e5aa946 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_icm20689.c @@ -0,0 +1,149 @@ +/* + * This file is part of iNavFlight. + * + * 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/debug.h" + +#include "common/axis.h" +#include "common/maths.h" + +#include "drivers/system.h" +#include "drivers/time.h" +#include "drivers/io.h" +#include "drivers/exti.h" +#include "drivers/bus.h" + +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_icm20689.h" + +#if (defined(USE_GYRO_ICM20689) || defined(USE_ACC_ICM20689)) + +static uint8_t icm20689DeviceDetect(const busDevice_t *busDev) +{ + busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); + + busWrite(busDev, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); + + uint8_t attemptsRemaining = 20; + uint8_t in; + do { + delay(150); + busRead(busDev, MPU_RA_WHO_AM_I, &in); + switch (in) { + case ICM20601_WHO_AM_I_CONST: + case ICM20602_WHO_AM_I_CONST: + case ICM20608G_WHO_AM_I_CONST: + case ICM20689_WHO_AM_I_CONST: + return true; + } + } while (attemptsRemaining--); + + return false; +} + +static void icm20689AccInit(accDev_t *acc) +{ + acc->acc_1G = 512 * 4; +} + +bool icm20689AccDetect(accDev_t *acc) +{ + acc->busDev = busDeviceOpen(BUSTYPE_ANY, DEVHW_ICM20689, acc->imuSensorToUse); + if (acc->busDev == NULL) { + return false; + } + + mpuContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev); + if (ctx->chipMagicNumber != 0x50D1) { + return false; + } + + acc->initFn = icm20689AccInit; + acc->readFn = mpuAccReadScratchpad; + + return true; +} + +static void icm20689AccAndGyroInit(gyroDev_t *gyro) +{ + busDevice_t * busDev = gyro->busDev; + const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); + gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; + + gyroIntExtiInit(gyro); + + busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); + + busWrite(busDev, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); + delay(100); + busWrite(busDev, MPU_RA_SIGNAL_PATH_RESET, 0x03); + delay(100); + busWrite(busDev, MPU_RA_PWR_MGMT_1, INV_CLK_PLL); + delay(15); + busWrite(busDev, MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); // XXX + delay(15); + busWrite(busDev, MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3); + delay(15); + busWrite(busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]); + delay(15); + busWrite(busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); // Get Divider Drops + delay(100); + + // Data ready interrupt configuration + busWrite(busDev, MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR, BYPASS_EN + + delay(15); + +#ifdef USE_MPU_DATA_READY_SIGNAL + busWrite(busDev, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable +#endif +} + +bool icm20689GyroDetect(gyroDev_t *gyro) +{ + gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_ICM20689, gyro->imuSensorToUse, OWNER_MPU); + if (gyro->busDev == NULL) { + return false; + } + + if (!icm20689DeviceDetect(gyro->busDev)) { + busDeviceDeInit(gyro->busDev); + return false; + } + + // Magic number for ACC detection to indicate that we have detected MPU6000 gyro + mpuContextData_t * ctx = busDeviceGetScratchpadMemory(gyro->busDev); + ctx->chipMagicNumber = 0x50D1; + + gyro->initFn = icm20689AccAndGyroInit; + gyro->readFn = mpuGyroReadScratchpad; + gyro->intStatusFn = gyroCheckDataReady; + gyro->temperatureFn = mpuTemperatureReadScratchpad; + gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor + + return true; +} + +#endif diff --git a/src/main/drivers/accgyro/accgyro_icm20689.h b/src/main/drivers/accgyro/accgyro_icm20689.h new file mode 100644 index 00000000000..bf37b1d4ad2 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_icm20689.h @@ -0,0 +1,32 @@ +/* + * This file is part of iNavFlight. + * + * 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 + +#include "drivers/bus.h" + +#define ICM20689_BIT_RESET (0x80) + +#if (defined(USE_GYRO_ICM20689) || defined(USE_ACC_ICM20689)) + +bool icm20689AccDetect(accDev_t *acc); +bool icm20689GyroDetect(gyroDev_t *gyro); + +#endif diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index c171323bc25..6964127754b 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -83,6 +83,7 @@ typedef enum { DEVHW_MPU6050, DEVHW_MPU6500, DEVHW_BMI160, + DEVHW_ICM20689, /* Combined ACC/GYRO/MAG chips */ DEVHW_MPU9250, diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index f04676bff2f..53ec080dee3 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -36,7 +36,7 @@ #include "serial_uart_impl.h" static void usartConfigurePinInversion(uartPort_t *uartPort) { -#if !defined(USE_UART_INVERTER) && !defined(STM32F303xC) +#if !defined(USE_UART_INVERTER) && !defined(STM32F303xC) && !defined(STM32F7) UNUSED(uartPort); #else bool inverted = uartPort->port.options & SERIAL_INVERTED; diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index d246db6dc88..85c6250455a 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -149,7 +149,7 @@ static const char * const featureNames[] = { /* Sensor names (used in lookup tables for *_hardware settings and in status command output) */ // sync with gyroSensor_e -static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"}; +static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"}; // sync this with sensors_e static const char * const sensorTypeNames[] = { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 03221d2f87d..4f0a6c09fa2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -4,7 +4,7 @@ tables: - name: gyro_lpf values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"] - name: acc_hardware - values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"] + values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"] enum: accelerationSensor_e - name: rangefinder_hardware values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"] diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 495ebb62ef7..15267f96637 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -47,6 +47,7 @@ #include "drivers/accgyro/accgyro_mma845x.h" #include "drivers/accgyro/accgyro_bma280.h" #include "drivers/accgyro/accgyro_bmi160.h" +#include "drivers/accgyro/accgyro_icm20689.h" #include "drivers/accgyro/accgyro_fake.h" #include "drivers/logging.h" #include "drivers/sensor.h" @@ -266,6 +267,23 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) FALLTHROUGH; #endif +#ifdef USE_ACC_ICM20689 + case ACC_ICM20689: + if (icm20689AccDetect(dev)) { +#ifdef ACC_ICM20689_ALIGN + dev->accAlign = ACC_ICM20689_ALIGN; +#endif + accHardware = ACC_ICM20689; + break; + } + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (accHardwareToUse != ACC_AUTODETECT) { + break; + } + FALLTHROUGH; +#endif + + #ifdef USE_FAKE_ACC case ACC_FAKE: if (fakeAccDetect(dev)) { diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index e02e654ba6c..91df04db0ac 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -44,7 +44,8 @@ typedef enum { ACC_MPU6500 = 8, ACC_MPU9250 = 9, ACC_BMI160 = 10, - ACC_FAKE = 11, + ACC_ICM20689 = 11, + ACC_FAKE = 12, ACC_MAX = ACC_FAKE } accelerationSensor_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index bafd943247a..8bfca6b05c2 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -48,6 +48,7 @@ #include "drivers/accgyro/accgyro_mma845x.h" #include "drivers/accgyro/accgyro_bma280.h" #include "drivers/accgyro/accgyro_bmi160.h" +#include "drivers/accgyro/accgyro_icm20689.h" #include "drivers/accgyro/accgyro_fake.h" #include "drivers/io.h" #include "drivers/logging.h" @@ -221,6 +222,18 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard FALLTHROUGH; #endif +#ifdef USE_GYRO_ICM20689 + case GYRO_ICM20689: + if (icm20689GyroDetect(dev)) { + gyroHardware = GYRO_ICM20689; +#ifdef GYRO_ICM20689_ALIGN + dev->gyroAlign = GYRO_ICM20689_ALIGN; +#endif + break; + } + FALLTHROUGH; +#endif + #ifdef USE_FAKE_GYRO case GYRO_FAKE: if (fakeGyroDetect(dev)) { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index f145b11c9fc..92330913079 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -35,6 +35,7 @@ typedef enum { GYRO_MPU6500, GYRO_MPU9250, GYRO_BMI160, + GYRO_ICM20689, GYRO_FAKE } gyroSensor_e; diff --git a/src/main/target/KAKUTEF7/target.c b/src/main/target/KAKUTEF7/target.c new file mode 100755 index 00000000000..0dd1f8b4034 --- /dev/null +++ b/src/main/target/KAKUTEF7/target.c @@ -0,0 +1,46 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it 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. + * + * This file is distributed in the hope that it 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 program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_icm20689, DEVHW_ICM20689, ICM20689_SPI_BUS, ICM20689_CS_PIN, ICM20689_EXTI_PIN, 0, DEVFLAGS_NONE); + +const timerHardware_t timerHardware[] = { + { TIM1, IO_TAG(PE13), TIM_CHANNEL_3, 0, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_PPM }, // PPM + + { TIM3, IO_TAG(PB0), TIM_CHANNEL_3, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // MOTOR_1 + { TIM3, IO_TAG(PB1), TIM_CHANNEL_4, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // MOTOR_2 + { TIM1, IO_TAG(PE9), TIM_CHANNEL_1, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3 + { TIM1, IO_TAG(PE11), TIM_CHANNEL_2, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_4 + { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, 1, IOCFG_AF_PP_PD, GPIO_AF3_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_5 + { TIM5, IO_TAG(PA3), TIM_CHANNEL_4, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_6 + + { TIM4, IO_TAG(PD12), TIM_CHANNEL_1, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM4, TIM_USE_LED } +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h new file mode 100644 index 00000000000..ac87b45e180 --- /dev/null +++ b/src/main/target/KAKUTEF7/target.h @@ -0,0 +1,160 @@ +/* + * This file is part of INAV. + * + * 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 + +//#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "KTF7" +#define USBD_PRODUCT_STRING "KakuteF7" + +#define LED0 PA2 + +#define BEEPER PD15 +#define BEEPER_INVERTED + +#define USE_ACC +#define USE_GYRO + +#define USE_MPU_DATA_READY_SIGNAL +#define USE_EXTI + +// ICM-20689 +#define USE_ACC_ICM20689 +#define USE_GYRO_ICM20689 +#define GYRO_ICM20689_ALIGN CW270_DEG +#define ACC_ICM20689_ALIGN CW270_DEG + +#define ICM20689_EXTI_PIN PE1 +#define ICM20689_CS_PIN SPI4_NSS_PIN +#define ICM20689_SPI_BUS BUS_SPI4 + +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_ENABLED +#define VBUS_SENSING_PIN PA8 + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN NONE +#define UART7_RX_PIN PE7 + +#define SERIAL_PORT_COUNT 7 //VCP,UART1,UART2,UART3,UART4,UART6,UART7 + +#define USE_SPI +#define USE_SPI_DEVICE_1 //SD Card +#define USE_SPI_DEVICE_2 //OSD +#define USE_SPI_DEVICE_4 //ICM20689 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI4_NSS_PIN PE4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +#define USE_SDCARD +#define SDCARD_DETECT_INVERTED +#define SDCARD_DETECT_PIN PD8 + +#define SDCARD_SPI_INSTANCE SPI1 +#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN + +#define SDCARD_DMA_CHANNEL_TX DMA2_Stream5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF1_5 // XXX not sure if that's good +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2 +#define SDCARD_DMA_CHANNEL DMA_CHANNEL_3 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_BARO +#define USE_BARO_BMP280 +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define MAG_HMC5883_ALIGN CW180_DEG +#define USE_MAG_QMC5883 +#define USE_MAG_MAG3110 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_LIS3MDL + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC5 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART6 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 6 diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk new file mode 100755 index 00000000000..037f63f7a9c --- /dev/null +++ b/src/main/target/KAKUTEF7/target.mk @@ -0,0 +1,16 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro/accgyro_icm20689.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/compass/compass_ak8963.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stdperiph.c \ + drivers/max7456.c