From 03263adf59508f8fa69da1b691e96736ebf3c41c Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Mon, 31 Oct 2022 10:03:58 -0500 Subject: [PATCH 01/37] fix mixer.c for when undefining USE_BRUSHED_ESC_AUTODETECT (#854) --- src/main/flight/mixer.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index c770411096..55b5d9cfd7 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -759,7 +759,12 @@ float applyThrottleLimit(float throttle) { void mixWithThrottleLegacy(float *motorMix, float *controllerMix, float controllerMixMin, float controllerMixMax) { float throttleThrust = currentPidProfile->linear_throttle ? throttle : motorToThrust(throttle, true); + +#ifdef USE_BRUSHED_ESC_AUTODETECT float normFactor = 1 / (controllerMixRange > 1.0f && hardwareMotorType != MOTOR_BRUSHED ? controllerMixRange : 1.0f); +#else + float normFactor = 1 / (controllerMixRange > 1.0f ? controllerMixRange : 1.0f); +#endif if (mixerImpl == MIXER_IMPL_LEGACY) { // legacy clipping handling From 1ff18fc89edad5de4e7cbc9b04fd550e17f68c09 Mon Sep 17 00:00:00 2001 From: Kevin Plaizier <46289813+Quick-Flash@users.noreply.github.com> Date: Wed, 3 May 2023 08:02:30 -0600 Subject: [PATCH 02/37] Fix the correction yaw gives in 2pass (#852) * fix the correction yaw gives in 2pass * fix issue on lazy mixer * Update mixer.c * fix a problem when it is outside the 0-1 range but still has a range of 1 * fix a problem when it is outside the 0-1 range but still has a range of 1 * This time dangit --------- --- src/main/flight/mixer.c | 41 ++++++++++++++++++++++++++++++----------- 1 file changed, 30 insertions(+), 11 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 55b5d9cfd7..66d510837a 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -1009,13 +1009,10 @@ static void twoPassMix(float *motorMix, const float *yawMix, const float *rollPi // filling up motorMix with throttle, and yaw for (int i = 0; i < motorCount; i++) { - motorMix[i] = throttleMotor; // motorMix have to contain output-proportional values - - // clipping handling + // clipping handling float yawOffset = mixerLaziness ? (ABS(yawMix[i]) * SCALE_UNITARY_RANGE(throttleMotor, 1, -1)) : SCALE_UNITARY_RANGE(throttleMotor, -yawMixMin, -yawMixMax); - - motorMix[i] += (yawMix[i] + yawOffset) * controllerMixNormFactor; // yaw is an output-proportional value (RPM-proportional, actually) + motorMix[i] = throttleMotor + (yawMix[i] + yawOffset) * controllerMixNormFactor; // yaw is an output-proportional value (RPM-proportional, actually) postYawThrottle += motorMix[i]; if (motorMix[i] > maxMotorYawMix) { @@ -1030,21 +1027,43 @@ static void twoPassMix(float *motorMix, const float *yawMix, const float *rollPi // deal with yaw throttle correction values that would cause motor outputs that are greater or less than 1 yawThrottleCorrection = constrainf(yawThrottleCorrection, maxMotorYawMix - 1.0f, minMotorYawMix); + float throttlePostYaw = postYawThrottle - yawThrottleCorrection; + float thrustPostYaw = motorToThrust(throttlePostYaw, true); + + float maxMotor = -1000.0; + float minMotor = 1000.0; + // correct for the extra thrust yaw adds, then fill up motorMix with pitch and roll for (int i = 0; i < motorCount; i++) { - if (currentPidProfile->mixer_yaw_throttle_comp) { //!==0 // prefer calculating all of the above and maybe not use it, than multiple if/then statements to save from calculating. motorMix[i] = motorMix[i] - yawThrottleCorrection; }; - float motorMixThrust = motorToThrust(motorMix[i], true); // convert into thrust value + motorMix[i] = motorToThrust(motorMix[i], true); // convert into thrust value // clipping handling - float rollPitchOffset = mixerLaziness ? (ABS(rollPitchMix[i]) * SCALE_UNITARY_RANGE(motorMixThrust, 1, -1)) - : SCALE_UNITARY_RANGE(motorMixThrust, -rollPitchMixMin, -rollPitchMixMax); + float rollPitchOffset = mixerLaziness ? (ABS(rollPitchMix[i]) * SCALE_UNITARY_RANGE(thrustPostYaw , 1, -1)) + : SCALE_UNITARY_RANGE(thrustPostYaw , -rollPitchMixMin, -rollPitchMixMax); + motorMix[i] += (rollPitchOffset + rollPitchMix[i]) * controllerMixNormFactor; // roll and pitch are thrust-proportional values + if (motorMix[i] > maxMotor) { + maxMotor = motorMix[i]; + } + if (motorMix[i] < minMotor) { + minMotor = motorMix[i]; + } + } - motorMixThrust += (rollPitchOffset + rollPitchMix[i]) * controllerMixNormFactor; // roll and pitch are thrust-proportional values + // if the range is outside the normal bounds, correct it here + float motorCorrection = 0.0; + if (maxMotor > 1.0) { + motorCorrection = 1.0 - maxMotor; + } else if (minMotor < 0.0) { + motorCorrection = -minMotor; + } + + for (int i = 0; i < motorCount; i++) { + motorMix[i] += motorCorrection; - motorMix[i] = thrustToMotor(motorMixThrust, true); // translating back into motor value + motorMix[i] = thrustToMotor(motorMix[i], true); // translating back into motor value } } From 2e7cc1d53c3b4bf7810a2c68fb145cb3572d26d9 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 4 May 2023 07:34:40 -0500 Subject: [PATCH 03/37] =?UTF-8?q?github=20actions=20-=20remove=20fiam=20ar?= =?UTF-8?q?m=5Fsdk=20action=20and=20revert=20to=20Makefile's=20=E2=80=A6?= =?UTF-8?q?=20(#884)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit github actions - remove fiam arm_sdk action and revert to Makefile's arm_sdk with caching Co-authored-by: Mathias Rasmussen --- .github/workflows/build.yml | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 4b46b9ac94..ed938545a9 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -33,10 +33,21 @@ jobs: run: function curl () { command curl --connect-timeout 30 --retry 10 "$@" ; } - name: Checkout - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: fetch-depth: 0 + - name: Cache build toolchain + uses: actions/cache@v3 + id: cache-toolchain + with: + path: tools + key: ${{ runner.os }}-${{ hashFiles('make/tools.mk') }} + + - name: Download and install toolchain + if: steps.cache-toolchain.outputs.cache-hit != 'true' + run: make arm_sdk_install + - name: Take the trash out run: | sudo swapoff -a @@ -50,12 +61,6 @@ jobs: - name: Setup Python uses: actions/setup-python@v2 - - name: Setup Toolchain - uses: fiam/arm-none-eabi-gcc@v1 - #uses: emuflight/arm-none-eabi-gcc@retry_timeout - with: - release: '9-2020-q2' # The arm-none-eabi-gcc release to use. - # EmuFlight version - name: Get code version id: get_version From 11e44022e4abda6c0235dac0fda9999cb5801d7e Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 4 May 2023 08:59:50 -0500 Subject: [PATCH 04/37] DFRF722DUALHD define gyro 2 pin correctly (#883) Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> --- src/main/target/DFRF722DUALHD/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/DFRF722DUALHD/target.h b/src/main/target/DFRF722DUALHD/target.h index 6cdd27bb9d..ed4c5df3e0 100644 --- a/src/main/target/DFRF722DUALHD/target.h +++ b/src/main/target/DFRF722DUALHD/target.h @@ -46,7 +46,7 @@ #define MPU_INT_EXTI #define USE_GYRO_EXTI #define GYRO_1_EXTI_PIN PA8 -#define GYRO_2_EXTI_PIN PC13 +#define GYRO_2_EXTI_PIN PB2 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW From c6022f8d1136dd2eb3326cb20d8dc8a00362726c Mon Sep 17 00:00:00 2001 From: Igor Shpakov Date: Thu, 4 May 2023 21:20:13 +0100 Subject: [PATCH 05/37] Add cliDebugPrint functions to facilitate easy debug printing to CLI (#448) port of https://github.com/betaflight/betaflight/pull/8905 thanks to @etracer65 for original commit in betalfight To use, include cli/cli_debug_print.h in your code and be sure USE_CLI_DEBUG_PRINT is defined. Or alternately, build using make TARGET= OPTIONS="USE_CLI_DEBUG_PRINT". Then you'll have access to the following functions to print debugging messages in the CLI: cliDebugPrintLineFeed cliDebugPrint cliDebugPrintLine cliDebugPrintf cliDebugPrintLinef Output is suppressed when the CLI is not open. The functions are equivalent to their cliPrint... counterparts. May interfere with the autocomplete initialization when first entering the CLI if your code is outputting data when the CLI first opens. But as this is only meant for debugging it shouldn't be much of a concern. You may also need to rate limit your messages if printing data in a loop. Using these calls in other modules should only used for debugging and not left in any finished code. Co-authored-by: Igor Shpakov Co-authored-by: etracer65 --- src/main/interface/cli.c | 22 +++++++++---- src/main/interface/cli.h | 8 +++++ src/main/interface/cli_debug_print.h | 49 ++++++++++++++++++++++++++++ 3 files changed, 73 insertions(+), 6 deletions(-) create mode 100644 src/main/interface/cli_debug_print.h diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c index f79a8f6697..80bac75d60 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -283,7 +283,10 @@ static void backupAndResetConfigs(void) { resetConfigs(); } -static void cliPrint(const char *str) { +void cliPrint(const char *str) { + if (!cliMode) { + return; + } while (*str) { if(cliSmartMode) { //no carriage returns. Those are dumb. @@ -299,14 +302,14 @@ static void cliPrint(const char *str) { bufWriterFlush(cliWriter); } -static void cliPrintLinefeed(void) { +void cliPrintLinefeed(void) { cliPrint("\r\n"); if(cliSmartMode) { bufWriterFlush(cliWriter); } } -static void cliPrintLine(const char *str) { +void cliPrintLine(const char *str) { cliPrint(str); cliPrintLinefeed(); } @@ -370,7 +373,10 @@ static bool cliDefaultPrintLinef(uint8_t dumpMask, bool equalsDefault, const cha } } -static void cliPrintf(const char *format, ...) { +void cliPrintf(const char *format, ...) { + if (!cliMode) { + return; + } va_list va; va_start(va, format); cliPrintfva(format, va); @@ -378,7 +384,11 @@ static void cliPrintf(const char *format, ...) { } -static void cliPrintLinef(const char *format, ...) { +void cliPrintLinef(const char *format, ...) { + if (!cliMode) { + return; + } + va_list va; va_start(va, format); cliPrintfva(format, va); @@ -2395,7 +2405,7 @@ void cliRxBind(char *cmdline) { case RX_SPI_REDPINE: case RX_SPI_SFHSS: cc2500SpiBind(); - cliPrint("Binding..."); + cliPrintf("Binding..."); break; #endif default: diff --git a/src/main/interface/cli.h b/src/main/interface/cli.h index 41796d0c19..3a3d5e6273 100644 --- a/src/main/interface/cli.h +++ b/src/main/interface/cli.h @@ -32,3 +32,11 @@ void cliInit(const struct serialConfig_s *serialConfig); void cliProcess(void); struct serialPort_s; void cliEnter(struct serialPort_s *serialPort); + +#ifdef USE_CLI_DEBUG_PRINT +void cliPrint(const char *str); +void cliPrintLinefeed(void); +void cliPrintLine(const char *str); +void cliPrintf(const char *format, ...); +void cliPrintLinef(const char *format, ...); +#endif diff --git a/src/main/interface/cli_debug_print.h b/src/main/interface/cli_debug_print.h new file mode 100644 index 0000000000..afe0329b4b --- /dev/null +++ b/src/main/interface/cli_debug_print.h @@ -0,0 +1,49 @@ +/* + * 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 . + */ + +// Provides: cliPrintDebug... functions for displaying debugging information in the CLI +// +// Usage: Make sure USE_CLI_DEBUG_PRINT is defined +// Include this header in your code +// Add cliDebugPrint... statements as needed in your code +// Use the CLI to see the output of the debugging statements +// +// Cautions: Be sure to include rate limiting logic to your debug printing +// if needed otherwise you can flood the output. +// +// Be sure to reverse the Usage steps above to remove the debugging +// elements before submitting final code. + +#include "platform.h" + +#ifdef USE_CLI_DEBUG_PRINT + +#include "interface/cli.h" + +// Commands to print debugging information to the CLI +#define cliDebugPrintLinefeed cliPrintLinefeed +#define cliDebugPrintLinef cliPrintLinef +#define cliDebugPrintLine cliPrintLine +#define cliDebugPrintf cliPrintf +#define cliDebugPrint cliPrint + +#else +#error "Do not #include cli_debug_print.h unless you intend to do debugging and also define USE_CLI_DEBUG_PRINT" +#endif From bb311eb4cee1f18d56ec1bfd08841b18bb84a84d Mon Sep 17 00:00:00 2001 From: Kevin Plaizier <46289813+Quick-Flash@users.noreply.github.com> Date: Thu, 11 May 2023 10:02:58 -0600 Subject: [PATCH 06/37] Fix helio attitude estimation (STABLE-MODE) (ACC/GYRO) (#886) * Update gyro.c * scale ACC for Helio too --------- Co-authored-by: nerdCopter <56646290+nerdCopter@users.noreply.github.com> --- src/main/interface/msp.c | 8 ++++++-- src/main/sensors/gyro.c | 17 ++++++----------- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index 8392f3ed67..b3aebb427d 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -745,7 +745,7 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { case MSP_RAW_IMU: { // Hack scale due to choice of units for sensor data in multiwii uint8_t scale = 1; -#ifndef USE_GYRO_IMUF9001 +//#ifndef USE_GYRO_IMUF9001 if (acc.dev.acc_1G > 512 * 4) { scale = 8; } else if (acc.dev.acc_1G > 512 * 2) { @@ -753,12 +753,16 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { } else if (acc.dev.acc_1G >= 512) { scale = 2; } -#endif //USE_GYRO_IMUF9001 +//#endif //USE_GYRO_IMUF9001 for (int i = 0; i < 3; i++) { sbufWriteU16(dst, lrintf(acc.accADC[i] / scale)); } for (int i = 0; i < 3; i++) { +#ifdef USE_GYRO_IMUF9001 + sbufWriteU16(dst, gyroRateDps(i) * scale); +#else sbufWriteU16(dst, gyroRateDps(i)); +#endif } for (int i = 0; i < 3; i++) { sbufWriteU16(dst, lrintf(mag.magADC[i])); diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 95e0d370e8..60d6a62df3 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -1141,11 +1141,6 @@ static FAST_CODE_NOINLINE void gyroUpdateSensor(gyroSensor_t* gyroSensor, timeUs for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { // NOTE: this branch optimized for when there is no gyro debugging, ensure it is kept in step with non-optimized branch DEBUG_SET(DEBUG_GYRO_SCALED, axis, lrintf(gyroSensor->gyroDev.gyroADCf[axis])); - if (!gyroSensor->overflowDetected) { - // integrate using trapezium rule to avoid bias - accumulatedMeasurements[axis] += 0.5f * (gyroPrevious[axis] + gyro.gyroADCf[axis]) * gyro.targetLooptime; - gyroPrevious[axis] = gyroSensor->gyroDev.gyroADCf[axis]; - } } if (!isGyroSensorCalibrationComplete(gyroSensor)) { performGyroCalibration(gyroSensor, gyroConfig()->gyroMovementCalibrationThreshold); @@ -1298,7 +1293,7 @@ FAST_CODE_NOINLINE void gyroUpdate(timeUs_t currentTimeUs) { if (!overflowDetected) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { // integrate using trapezium rule to avoid bias - accumulatedMeasurements[axis] += 0.5f * (gyroPrevious[axis] + gyro.gyroADCf[axis]) * gyro.targetLooptime; + accumulatedMeasurements[axis] += (gyroPrevious[axis] + gyro.gyroADCf[axis]); gyroPrevious[axis] = gyro.gyroADCf[axis]; } accumulatedMeasurementCount++; @@ -1307,11 +1302,11 @@ FAST_CODE_NOINLINE void gyroUpdate(timeUs_t currentTimeUs) { bool gyroGetAverage(quaternion *vAverage) { if (accumulatedMeasurementCount) { - const timeUs_t accumulatedMeasurementTimeUs = accumulatedMeasurementCount * gyro.targetLooptime; + const timeUs_t accumulatedMeasurementTimeUs = accumulatedMeasurementCount; vAverage->w = 0; - vAverage->x = DEGREES_TO_RADIANS(accumulatedMeasurements[X] / accumulatedMeasurementTimeUs); - vAverage->y = DEGREES_TO_RADIANS(accumulatedMeasurements[Y] / accumulatedMeasurementTimeUs); - vAverage->z = DEGREES_TO_RADIANS(accumulatedMeasurements[Z] / accumulatedMeasurementTimeUs); + vAverage->x = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[X] / accumulatedMeasurementTimeUs); + vAverage->y = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[Y] / accumulatedMeasurementTimeUs); + vAverage->z = 0.5f * DEGREES_TO_RADIANS(accumulatedMeasurements[Z] / accumulatedMeasurementTimeUs); for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { accumulatedMeasurements[axis] = 0.0f; } @@ -1413,4 +1408,4 @@ void initYawSpinRecovery(int maxYawRate) yawSpinRecoveryEnabled = enabledFlag; yawSpinRecoveryThreshold = threshold; } -#endif \ No newline at end of file +#endif From 4d731cd4908b42e6b3067e7da9f5bc416c43898f Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 11 May 2023 14:25:52 -0500 Subject: [PATCH 07/37] bump version 0.4.2 (#888) --- src/main/build/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/build/version.h b/src/main/build/version.h index ed00a47c31..562af0c0d2 100644 --- a/src/main/build/version.h +++ b/src/main/build/version.h @@ -25,7 +25,7 @@ #define FC_FIRMWARE_NAME "EmuFlight" #define FC_VERSION_MAJOR 0 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed +#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed #define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL) From 53a8da3e0e22e1fae9819119883a4687f9bc1fff Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 1 Jun 2023 12:54:32 -0500 Subject: [PATCH 08/37] initial ICM426xx support (#891) * ICM426xx - very dont know * ICM426xx - FOXEERF722V4 * ICM426xx - ICM_42688P & ICM_42605 ; CAUTION / really no idea if this is anything good * ICM426xx - more ICM_42688P & ICM_42605 ; CAUTION / really no idea if this is anything good * ICM426xx - FOXEERF745V3_AIO * ICM426xx - very dont know, part deaux * ICM426xx - very dont know, RUSHBLADEF7HD * ICM426xx - same; add accgyro_mpu.c; add icm 42688p to BETAFPVF722 * ICM426xx - still finding missing elements * ICM426xx - acc/gyro read change for icm426xx (@Peck07 fix to make it functional) * ICM426xx - DIAT_MAMBAF405_2022B; WIP; untested * ICM426xx - Adding ICM4xxxx to GEPRCF722_AIO * ICM426xx - JHEF_JHEF7DUAL; WIP; untested * ICM426xx - JHEF_JHEF7DUAL; WIP; not working; no USB connect * ICM426xx - add CRAZYFLIE2 to unsupported targets due to build failure and obsolescence * ICM426xx - fix out of band #endif * ICM426xx - JHEF_JHEF7DUAL; WIP; untested * ICM426xx - modded existing JHEF7DUAL; new JHEF_JHEF7DUAL is not working * ICM426xx - fix BETAFPVF722 target * ICM426xx - fix JHEF_JHEF7DUAL target * ICM426xx - gyro_hardware_lpf modes * ICM426xx - define USE_GYRO_DLPF_EXPERIMENTAL * ICM426xx - add ICM42605_CS_PIN * ICM426xx - remove comma in lookupTableGyroHardwareLpf * ICM426xx - target resets and removal * ICM426xx - extra line removal --------- Co-authored-by: tbolin Co-authored-by: KarateBrot Co-authored-by: Steve Evans Co-authored-by: Dominic Clifton Co-authored-by: Peck07 <28628457+Peck07@users.noreply.github.com> Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> Co-authored-by: nerdCopter <56646290+nerdCopter@users.noreply.github.com> --- src/main/common/utils.h | 2 + src/main/drivers/accgyro/accgyro.h | 12 +- src/main/drivers/accgyro/accgyro_mpu.c | 27 ++ src/main/drivers/accgyro/accgyro_mpu.h | 6 +- .../drivers/accgyro/accgyro_spi_icm426xx.c | 389 ++++++++++++++++++ .../drivers/accgyro/accgyro_spi_icm426xx.h | 36 ++ .../drivers/accgyro/accgyro_spi_mpu6500.c | 6 + src/main/drivers/bus_spi.c | 27 ++ src/main/drivers/bus_spi.h | 5 + src/main/flight/pid.c | 2 +- src/main/interface/settings.c | 12 +- src/main/pg/bus_spi.c | 6 + src/main/sensors/acceleration.c | 26 ++ src/main/sensors/acceleration.h | 2 + src/main/sensors/gyro.c | 30 +- src/main/sensors/gyro.h | 2 + src/main/target/common_fc_pre.h | 3 + 17 files changed, 586 insertions(+), 7 deletions(-) create mode 100644 src/main/drivers/accgyro/accgyro_spi_icm426xx.c create mode 100644 src/main/drivers/accgyro/accgyro_spi_icm426xx.h diff --git a/src/main/common/utils.h b/src/main/common/utils.h index 8cd021d1ff..95f2716244 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -103,6 +103,8 @@ static inline int32_t cmp32(uint32_t a, uint32_t b) { return (int32_t)(a - b); } +static inline uint32_t llog2(uint32_t n) { return 31 - __builtin_clz(n | 1); } + // using memcpy_fn will force memcpy function call, instead of inlining it. In most cases function call takes fewer instructions // than inlined version (inlining is cheaper for very small moves < 8 bytes / 2 store instructions) #if defined(UNIT_TEST) || defined(SIMULATOR_BUILD) diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h index a29d931c25..2c17f4b2f5 100644 --- a/src/main/drivers/accgyro/accgyro.h +++ b/src/main/drivers/accgyro/accgyro.h @@ -38,12 +38,20 @@ #endif #define GYRO_HARDWARE_LPF_NORMAL 0 -#define GYRO_HARDWARE_LPF_EXPERIMENTAL 1 #define GYRO_HARDWARE_LPF_1KHZ_SAMPLE 2 +#if defined(USE_GYRO_SPI_ICM42688P) +#define GYRO_HARDWARE_LPF_EXPERIMENTAL 3 +#else +#define GYRO_HARDWARE_LPF_EXPERIMENTAL 1 +#endif + #define GYRO_32KHZ_HARDWARE_LPF_NORMAL 0 #define GYRO_32KHZ_HARDWARE_LPF_EXPERIMENTAL 1 +#define GYRO_HARDWARE_LPF_OPTION_1 1 +#define GYRO_HARDWARE_LPF_OPTION_2 2 + #define GYRO_LPF_256HZ 0 #define GYRO_LPF_188HZ 1 #define GYRO_LPF_98HZ 2 @@ -91,6 +99,8 @@ typedef struct gyroDev_s { ioTag_t mpuIntExtiTag; uint8_t gyroHasOverflowProtection; gyroSensor_e gyroHardware; + uint8_t accDataReg; + uint8_t gyroDataReg; } gyroDev_t; typedef struct accDev_s { diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 498536f8c2..5265e27342 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -55,6 +55,7 @@ #include "drivers/accgyro/accgyro_spi_bmi160.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" +#include "drivers/accgyro/accgyro_spi_icm426xx.h" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -365,6 +366,32 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro) { return true; } #endif +#ifdef USE_GYRO_SPI_ICM42605 +#ifdef ICM42605_SPI_INSTANCE + spiBusSetInstance(&gyro->bus, ICM42605_SPI_INSTANCE); +#endif +#ifdef ICM42605_CS_PIN + gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM42605_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin; +#endif + sensor = icm426xxSpiDetect(&gyro->bus); + if (sensor != MPU_NONE) { + gyro->mpuDetectionResult.sensor = sensor; + return true; + } +#endif +#ifdef USE_GYRO_SPI_ICM42688P +#ifdef ICM42688P_SPI_INSTANCE + spiBusSetInstance(&gyro->bus, ICM42688P_SPI_INSTANCE); +#endif +#ifdef ICM42688P_CS_PIN + gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(ICM42688P_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin; +#endif + sensor = icm426xxSpiDetect(&gyro->bus); + if (sensor != MPU_NONE) { + gyro->mpuDetectionResult.sensor = sensor; + return true; + } +#endif #ifdef USE_ACCGYRO_BMI160 #ifndef USE_DUAL_GYRO spiBusSetInstance(&gyro->bus, BMI160_SPI_INSTANCE); diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h index 550f05fe81..aa0f770e29 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.h +++ b/src/main/drivers/accgyro/accgyro_mpu.h @@ -29,7 +29,7 @@ //#define DEBUG_MPU_DATA_READY_INTERRUPT #if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20649) \ - || defined(USE_GYRO_SPI_ICM20689) + || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) #define GYRO_USES_SPI #endif @@ -47,6 +47,8 @@ #define ICM20608G_WHO_AM_I_CONST (0xAF) #define ICM20649_WHO_AM_I_CONST (0xE1) #define ICM20689_WHO_AM_I_CONST (0x98) +#define ICM42605_WHO_AM_I_CONST (0x42) +#define ICM42688P_WHO_AM_I_CONST (0x47) // RA = Register Address @@ -214,6 +216,8 @@ typedef enum { ICM_20608_SPI, ICM_20649_SPI, ICM_20689_SPI, + ICM_42605_SPI, + ICM_42688P_SPI, BMI_160_SPI, IMUF_9001_SPI, } mpuSensor_e; diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c new file mode 100644 index 0000000000..24003f9017 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -0,0 +1,389 @@ +/* + * 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" + +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) + +#include "common/axis.h" +#include "common/maths.h" + +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_spi_icm426xx.h" +#include "drivers/bus_spi.h" +#include "drivers/exti.h" +#include "drivers/io.h" +#include "drivers/sensor.h" +#include "drivers/time.h" + +// 24 MHz max SPI frequency +#define ICM426XX_MAX_SPI_CLK_HZ 24000000 + +#define ICM426XX_RA_REG_BANK_SEL 0x76 +#define ICM426XX_BANK_SELECT0 0x00 +#define ICM426XX_BANK_SELECT1 0x01 +#define ICM426XX_BANK_SELECT2 0x02 +#define ICM426XX_BANK_SELECT3 0x03 +#define ICM426XX_BANK_SELECT4 0x04 + +#define ICM426XX_RA_PWR_MGMT0 0x4E // User Bank 0 +#define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0) +#define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2) +#define ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF ((0 << 0) | (0 << 2)) +#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF (0 << 5) +#define ICM426XX_PWR_MGMT0_TEMP_DISABLE_ON (1 << 5) + +#define ICM426XX_RA_GYRO_CONFIG0 0x4F +#define ICM426XX_RA_ACCEL_CONFIG0 0x50 + +// --- Registers for gyro and acc Anti-Alias Filter --------- +#define ICM426XX_RA_GYRO_CONFIG_STATIC3 0x0C // User Bank 1 +#define ICM426XX_RA_GYRO_CONFIG_STATIC4 0x0D // User Bank 1 +#define ICM426XX_RA_GYRO_CONFIG_STATIC5 0x0E // User Bank 1 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC2 0x03 // User Bank 2 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC3 0x04 // User Bank 2 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 // User Bank 2 +// --- Register & setting for gyro and acc UI Filter -------- +#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 // User Bank 0 +#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4) +#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (15 << 0) +// ---------------------------------------------------------- + +#define ICM426XX_RA_GYRO_DATA_X1 0x25 // User Bank 0 +#define ICM426XX_RA_ACCEL_DATA_X1 0x1F // User Bank 0 + +#define ICM426XX_RA_INT_CONFIG 0x14 // User Bank 0 +#define ICM426XX_INT1_MODE_PULSED (0 << 2) +#define ICM426XX_INT1_MODE_LATCHED (1 << 2) +#define ICM426XX_INT1_DRIVE_CIRCUIT_OD (0 << 1) +#define ICM426XX_INT1_DRIVE_CIRCUIT_PP (1 << 1) +#define ICM426XX_INT1_POLARITY_ACTIVE_LOW (0 << 0) +#define ICM426XX_INT1_POLARITY_ACTIVE_HIGH (1 << 0) + +#define ICM426XX_RA_INT_CONFIG0 0x63 // User Bank 0 +#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR ((0 << 5) || (0 << 4)) +#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_DUPLICATE ((0 << 5) || (0 << 4)) // duplicate settings in datasheet, Rev 1.2. +#define ICM426XX_UI_DRDY_INT_CLEAR_ON_F1BR ((1 << 5) || (0 << 4)) +#define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_AND_F1BR ((1 << 5) || (1 << 4)) + +#define ICM426XX_RA_INT_CONFIG1 0x64 // User Bank 0 +#define ICM426XX_INT_ASYNC_RESET_BIT 4 +#define ICM426XX_INT_TDEASSERT_DISABLE_BIT 5 +#define ICM426XX_INT_TDEASSERT_ENABLED (0 << ICM426XX_INT_TDEASSERT_DISABLE_BIT) +#define ICM426XX_INT_TDEASSERT_DISABLED (1 << ICM426XX_INT_TDEASSERT_DISABLE_BIT) +#define ICM426XX_INT_TPULSE_DURATION_BIT 6 +#define ICM426XX_INT_TPULSE_DURATION_100 (0 << ICM426XX_INT_TPULSE_DURATION_BIT) +#define ICM426XX_INT_TPULSE_DURATION_8 (1 << ICM426XX_INT_TPULSE_DURATION_BIT) + +#define ICM426XX_RA_INT_SOURCE0 0x65 // User Bank 0 +#define ICM426XX_UI_DRDY_INT1_EN_DISABLED (0 << 3) +#define ICM426XX_UI_DRDY_INT1_EN_ENABLED (1 << 3) + +typedef enum { + ODR_CONFIG_8K = 0, + ODR_CONFIG_4K, + ODR_CONFIG_2K, + ODR_CONFIG_1K, + ODR_CONFIG_COUNT +} odrConfig_e; + +typedef enum { + AAF_CONFIG_258HZ = 0, + AAF_CONFIG_536HZ, + AAF_CONFIG_997HZ, + AAF_CONFIG_1962HZ, + AAF_CONFIG_COUNT +} aafConfig_e; + +typedef struct aafConfig_s { + uint8_t delt; + uint16_t deltSqr; + uint8_t bitshift; +} aafConfig_t; + +// Possible output data rates (ODRs) +static uint8_t odrLUT[ODR_CONFIG_COUNT] = { // see GYRO_ODR in section 5.6 + [ODR_CONFIG_8K] = 3, + [ODR_CONFIG_4K] = 4, + [ODR_CONFIG_2K] = 5, + [ODR_CONFIG_1K] = 6, +}; + +// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P +static aafConfig_t aafLUT42688[AAF_CONFIG_COUNT] = { // see table in section 5.3 + [AAF_CONFIG_258HZ] = { 6, 36, 10 }, + [AAF_CONFIG_536HZ] = { 12, 144, 8 }, + [AAF_CONFIG_997HZ] = { 21, 440, 6 }, + [AAF_CONFIG_1962HZ] = { 37, 1376, 4 }, +}; + +// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P +// actual cutoff differs slightly from those of the 42688P +static aafConfig_t aafLUT42605[AAF_CONFIG_COUNT] = { // see table in section 5.3 + [AAF_CONFIG_258HZ] = { 21, 440, 6 }, // actually 249 Hz + [AAF_CONFIG_536HZ] = { 39, 1536, 4 }, // actually 524 Hz + [AAF_CONFIG_997HZ] = { 63, 3968, 3 }, // actually 995 Hz + [AAF_CONFIG_1962HZ] = { 63, 3968, 3 }, // 995 Hz is the max cutoff on the 42605 +}; + +static void icm426xxSpiInit(const busDevice_t *bus) { + static bool hardwareInitialised = false; + if (hardwareInitialised) { + return; + } +#ifndef USE_DUAL_GYRO + IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0); + IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG); + IOHi(bus->busdev_u.spi.csnPin); +#endif + spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD); + hardwareInitialised = true; +} + +uint8_t icm426xxSpiDetect(const busDevice_t *bus) { + icm426xxSpiInit(bus); + spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_INITIALIZATION); //low speed + spiBusWriteRegister(bus, MPU_RA_PWR_MGMT_1, ICM426xx_BIT_RESET); + uint8_t icmDetected = MPU_NONE; + uint8_t attemptsRemaining = 20; + do { + delay(150); + const uint8_t whoAmI = spiBusReadRegister(bus, MPU_RA_WHO_AM_I); + switch (whoAmI) { + case ICM42605_WHO_AM_I_CONST: + icmDetected = ICM_42605_SPI; + break; + case ICM42688P_WHO_AM_I_CONST: + icmDetected = ICM_42688P_SPI; + break; + default: + icmDetected = MPU_NONE; + break; + } + if (icmDetected != MPU_NONE) { + break; + } + if (!attemptsRemaining) { + return MPU_NONE; + } + } while (attemptsRemaining--); + spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_STANDARD); + return icmDetected; +} + +void icm426xxAccInit(accDev_t *acc) { + acc->acc_1G = 512 * 4; +} + +bool icm426xxAccRead(accDev_t *acc) +{ + uint8_t data[6]; + + const bool ack = busReadRegisterBuffer(&acc->bus, ICM426XX_RA_ACCEL_DATA_X1, data, 6); + if (!ack) { + return false; + } + + acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]); + acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]); + acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]); + + return true; +} + +bool icm426xxSpiAccDetect(accDev_t *acc) { + switch (acc->mpuDetectionResult.sensor) { + case ICM_42605_SPI: + case ICM_42688P_SPI: + break; + default: + return false; + } + acc->initFn = icm426xxAccInit; + acc->readFn = icm426xxAccRead; + return true; +} + +static aafConfig_t getGyroAafConfig(const mpuSensor_e, const aafConfig_e); + +static void turnGyroAccOff(const gyroDev_t *gyro) +{ + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF); +} + +// Turn on gyro and acc on in Low Noise mode +static void turnGyroAccOn(const gyroDev_t *gyro) +{ + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF | ICM426XX_PWR_MGMT0_ACCEL_MODE_LN | ICM426XX_PWR_MGMT0_GYRO_MODE_LN); + delay(1); +} + +static void setUserBank(const gyroDev_t *gyro, const uint8_t user_bank) +{ + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_REG_BANK_SEL, user_bank & 7); +} + +void icm426xxGyroInit(gyroDev_t *gyro) +{ + mpuGyroInit(gyro); + + spiSetDivisor(gyro->bus.busdev_u.spi.instance, spiCalculateDivider(ICM426XX_MAX_SPI_CLK_HZ)); + + gyro->accDataReg = ICM426XX_RA_ACCEL_DATA_X1; + gyro->gyroDataReg = ICM426XX_RA_GYRO_DATA_X1; + + // Turn off ACC and GYRO so they can be configured + // See section 12.9 in ICM-42688-P datasheet v1.7 + setUserBank(gyro, ICM426XX_BANK_SELECT0); + turnGyroAccOff(gyro); + + // Configure gyro Anti-Alias Filter (see section 5.3 "ANTI-ALIAS FILTER") + const mpuSensor_e gyroModel = gyro->mpuDetectionResult.sensor; + aafConfig_t aafConfig = getGyroAafConfig(gyroModel, gyroConfig()->gyro_hardware_lpf); + setUserBank(gyro, ICM426XX_BANK_SELECT1); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC3, aafConfig.delt); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC4, aafConfig.deltSqr & 0xFF); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG_STATIC5, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); + + // Configure acc Anti-Alias Filter for 1kHz sample rate (see tasks.c) + aafConfig = getGyroAafConfig(gyroModel, AAF_CONFIG_258HZ); + setUserBank(gyro, ICM426XX_BANK_SELECT2); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC2, aafConfig.delt << 1); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC3, aafConfig.deltSqr & 0xFF); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG_STATIC4, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); + + // Configure gyro and acc UI Filters + setUserBank(gyro, ICM426XX_BANK_SELECT0); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_ACCEL_CONFIG0, ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY | ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY); + + // Configure interrupt pin + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG, ICM426XX_INT1_MODE_PULSED | ICM426XX_INT1_DRIVE_CIRCUIT_PP | ICM426XX_INT1_POLARITY_ACTIVE_HIGH); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG0, ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR); + + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED); + + uint8_t intConfig1Value = spiReadRegMsk(&gyro->bus, ICM426XX_RA_INT_CONFIG1); + // Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation" + intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT); + intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED); + + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1, intConfig1Value); + + // Turn on gyro and acc on again so ODR and FSR can be configured + turnGyroAccOn(gyro); + + // Get desired output data rate + uint8_t odrConfig; + const unsigned decim = llog2(gyro->mpuDividerDrops + 1); + if (gyro->gyroRateKHz && decim < ODR_CONFIG_COUNT) { + odrConfig = odrLUT[decim]; + } else { + odrConfig = odrLUT[ODR_CONFIG_1K]; + gyro->gyroRateKHz = GYRO_RATE_1_kHz; + } + + STATIC_ASSERT(INV_FSR_2000DPS == 3, INV_FSR_2000DPS_must_be_3_to_generate_correct_value); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_GYRO_CONFIG0, (3 - INV_FSR_2000DPS) << 5 | (odrConfig & 0x0F)); + delay(15); + + STATIC_ASSERT(INV_FSR_16G == 3, INV_FSR_16G_must_be_3_to_generate_correct_value); + spiBusWriteRegister(&gyro->bus, ICM426XX_RA_ACCEL_CONFIG0, (3 - INV_FSR_16G) << 5 | (odrConfig & 0x0F)); + delay(15); +} + +// MIGHT NOT work on STM32F7 +#define STATIC_DMA_DATA_AUTO static +//FAST_CODE bool mpuGyroReadSPI(gyroDev_t *gyro) +bool icm426xxGyroReadSPI(gyroDev_t *gyro) +{ + //static const uint8_t dataToSend[7] = {MPU_RA_GYRO_XOUT_H | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + STATIC_DMA_DATA_AUTO uint8_t dataToSend[7] = {ICM426XX_RA_GYRO_DATA_X1 | 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + //uint8_t data[7]; + STATIC_DMA_DATA_AUTO uint8_t data[7]; + + const bool ack = spiBusTransfer(&gyro->bus, dataToSend, data, 7); + if (!ack) { + return false; + } + + gyro->gyroADCRaw[X] = (int16_t)((data[1] << 8) | data[2]); + gyro->gyroADCRaw[Y] = (int16_t)((data[3] << 8) | data[4]); + gyro->gyroADCRaw[Z] = (int16_t)((data[5] << 8) | data[6]); + + return true; +} + +bool icm426xxSpiGyroDetect(gyroDev_t *gyro) { + switch (gyro->mpuDetectionResult.sensor) { + case ICM_42605_SPI: + case ICM_42688P_SPI: + break; + default: + return false; + } + + gyro->initFn = icm426xxGyroInit; + gyro->readFn = icm426xxGyroReadSPI; + + gyro->scale = (2000.0f / (1 << 15)); // 16.384 dps/lsb scalefactor for 2000dps sensors + + return true; +} + +static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig_e config) +{ + switch (gyroModel){ + case ICM_42605_SPI: + switch (config) { + case GYRO_HARDWARE_LPF_NORMAL: + return aafLUT42605[AAF_CONFIG_258HZ]; + case GYRO_HARDWARE_LPF_OPTION_1: + return aafLUT42605[AAF_CONFIG_536HZ]; + case GYRO_HARDWARE_LPF_OPTION_2: + return aafLUT42605[AAF_CONFIG_997HZ]; + default: + return aafLUT42605[AAF_CONFIG_258HZ]; + } + + case ICM_42688P_SPI: + default: + switch (config) { + case GYRO_HARDWARE_LPF_NORMAL: + return aafLUT42688[AAF_CONFIG_258HZ]; + case GYRO_HARDWARE_LPF_OPTION_1: + return aafLUT42688[AAF_CONFIG_536HZ]; + case GYRO_HARDWARE_LPF_OPTION_2: + return aafLUT42688[AAF_CONFIG_997HZ]; +#ifdef USE_GYRO_DLPF_EXPERIMENTAL + case GYRO_HARDWARE_LPF_EXPERIMENTAL: + return aafLUT42688[AAF_CONFIG_1962HZ]; +#endif + default: + return aafLUT42688[AAF_CONFIG_258HZ]; + } + } +} + +#endif // USE_GYRO_SPI_ICM42605 || USE_GYRO_SPI_ICM42688P diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.h b/src/main/drivers/accgyro/accgyro_spi_icm426xx.h new file mode 100644 index 0000000000..842fe6626e --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.h @@ -0,0 +1,36 @@ +/* + * 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 + +#include "drivers/bus.h" + +#define ICM426xx_BIT_RESET (0x80) + +bool icm426xxAccDetect(accDev_t *acc); +bool icm426xxGyroDetect(gyroDev_t *gyro); + +void icm426xxAccInit(accDev_t *acc); +void icm426xxGyroInit(gyroDev_t *gyro); + +uint8_t icm426xxSpiDetect(const busDevice_t *dev); + +bool icm426xxSpiAccDetect(accDev_t *acc); +bool icm426xxSpiGyroDetect(gyroDev_t *gyro); \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c index a39d053d7a..86bca64388 100644 --- a/src/main/drivers/accgyro/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro/accgyro_spi_mpu6500.c @@ -69,6 +69,12 @@ uint8_t mpu6500SpiDetect(const busDevice_t *bus) { case ICM20608G_WHO_AM_I_CONST: mpuDetected = ICM_20608_SPI; break; + case ICM42605_WHO_AM_I_CONST: + mpuDetected = ICM_42605_SPI; + break; + case ICM42688P_WHO_AM_I_CONST: + mpuDetected = ICM_42688P_SPI; + break; default: mpuDetected = MPU_NONE; } diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 93cec8510a..d42f0e6156 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -251,4 +251,31 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) { bus->bustype = BUSTYPE_SPI; bus->busdev_u.spi.instance = instance; } + +uint16_t spiCalculateDivider(uint32_t freq) +{ +#if defined(STM32F4) || defined(STM32G4) || defined(STM32F7) + uint32_t spiClk = SystemCoreClock / 2; +#elif defined(STM32H7) + uint32_t spiClk = 100000000; +#elif defined(AT32F4) + if(freq > 36000000){ + freq = 36000000; + } + uint32_t spiClk = system_core_clock / 2; +#else +#error "Base SPI clock not defined for this architecture" +#endif + uint16_t divisor = 2; + spiClk >>= 1; + for (; (spiClk > freq) && (divisor < 256); divisor <<= 1, spiClk >>= 1); + return divisor; +} + +// Wait for bus to become free, then read a byte of data where the register is ORed with 0x80 +uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg) +{ + return spiBusReadRegister(bus, reg | 0x80); +} + #endif diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 12d8d068a7..1fa4a0dab7 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -121,3 +121,8 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance); struct spiPinConfig_s; void spiPinConfigure(const struct spiPinConfig_s *pConfig); + +// Determine the divisor to use for a given bus frequency +uint16_t spiCalculateDivider(uint32_t freq); + +uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index bb6f1fbdbb..2344beb3d5 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -86,7 +86,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 2); #ifdef STM32F10X #define PID_PROCESS_DENOM_DEFAULT 1 -#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) +#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) #define PID_PROCESS_DENOM_DEFAULT 1 #else #define PID_PROCESS_DENOM_DEFAULT 2 diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 0b6664170c..9634ec73c8 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -109,13 +109,13 @@ const char * const lookupTableAccHardware[] = { "AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", - "BMI160", "ACC_IMUF9001", "FAKE" + "ICM42605", "ICM42688P", "BMI160", "ACC_IMUF9001", "FAKE" }; // sync with gyroSensor_e const char * const lookupTableGyroHardware[] = { "AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", - "BMI160", "GYRO_IMUF9001", "FAKE" + "ICM42605", "ICM42688P", "BMI160", "GYRO_IMUF9001", "FAKE" }; #if defined(USE_SENSOR_NAMES) || defined(USE_BARO) @@ -252,8 +252,16 @@ static const char * const lookupTableRxSpi[] = { static const char * const lookupTableGyroHardwareLpf[] = { "NORMAL", +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) + "OPTION1", + "OPTION2", +#if defined(USE_GYRO_SPI_ICM42688P) && defined(USE_GYRO_DLPF_EXPERIMENTAL) // will need bmi270 logic as well + "EXPERIMENTAL", +#endif +#else "EXPERIMENTAL", "1KHZ_SAMPLING" +#endif }; #ifdef USE_32K_CAPABLE_GYRO diff --git a/src/main/pg/bus_spi.c b/src/main/pg/bus_spi.c index a51b0e9378..3b1fcfa7a8 100644 --- a/src/main/pg/bus_spi.c +++ b/src/main/pg/bus_spi.c @@ -91,6 +91,12 @@ ioTag_t preinitIPUList[SPI_PREINIT_IPU_COUNT] = { #ifdef ICM20689_CS_PIN IO_TAG(ICM20689_CS_PIN), #endif +#ifdef ICM42605_CS_PIN + IO_TAG(ICM42605_CS_PIN), +#endif +#ifdef ICM42688P_CS_PIN + IO_TAG(ICM42688P_CS_PIN), +#endif #ifdef BMI160_CS_PIN IO_TAG(BMI160_CS_PIN), #endif diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 1d1f08b132..62460a182c 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -45,6 +45,7 @@ #include "drivers/accgyro/accgyro_spi_bmi160.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" +#include "drivers/accgyro/accgyro_spi_icm426xx.h" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -298,6 +299,31 @@ bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) { } FALLTHROUGH; #endif +#if defined(USE_ACC_SPI_ICM42605) || defined(USE_ACC_SPI_ICM42688P) + case ACC_ICM42605: + case ACC_ICM42688P: + if (icm426xxSpiAccDetect(dev)) { + switch (dev->mpuDetectionResult.sensor) { + case ICM_42605_SPI: + accHardware = ACC_ICM42605; +#ifdef ACC_ICM42605_ALIGN + dev->accAlign = ACC_ICM42605_ALIGN; +#endif + break; + case ICM_42688P_SPI: + accHardware = ACC_ICM42688P; +#ifdef ACC_ICM42688P_ALIGN + dev->accAlign = ACC_ICM42688P_ALIGN; +#endif + break; + default: + accHardware = ACC_NONE; + break; + } + 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 778263ee37..b448d2419b 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -47,6 +47,8 @@ typedef enum { ACC_ICM20608G, ACC_ICM20649, ACC_ICM20689, + ACC_ICM42605, + ACC_ICM42688P, ACC_BMI160, ACC_IMUF9001, ACC_FAKE diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 60d6a62df3..b77528e9fd 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -46,6 +46,7 @@ #include "drivers/accgyro/accgyro_spi_bmi160.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" +#include "drivers/accgyro/accgyro_spi_icm426xx.h" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -208,7 +209,7 @@ static void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int typ #ifdef STM32F10X #define GYRO_SYNC_DENOM_DEFAULT 8 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \ - || defined(USE_GYRO_SPI_ICM20689) + || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) #define GYRO_SYNC_DENOM_DEFAULT 1 #else #define GYRO_SYNC_DENOM_DEFAULT 3 @@ -496,6 +497,31 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) { } FALLTHROUGH; #endif +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) + case GYRO_ICM42605: + case GYRO_ICM42688P: + if (icm426xxSpiGyroDetect(dev)) { + switch (dev->mpuDetectionResult.sensor) { + case ICM_42605_SPI: + gyroHardware = GYRO_ICM42605; +#ifdef GYRO_ICM42605_ALIGN + dev->gyroAlign = GYRO_ICM42605_ALIGN; +#endif + break; + case ICM_42688P_SPI: + gyroHardware = GYRO_ICM42688P; +#ifdef GYRO_ICM42688P_ALIGN + dev->gyroAlign = GYRO_ICM42688P_ALIGN; +#endif + break; + default: + gyroHardware = GYRO_NONE; + break; + } + break; + } + FALLTHROUGH; +#endif #ifdef USE_ACCGYRO_BMI160 case GYRO_BMI160: if (bmi160SpiGyroDetect(dev)) { @@ -536,7 +562,7 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) { static bool gyroInitSensor(gyroSensor_t *gyroSensor) { gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr; #if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \ - || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160) + || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160) mpuDetect(&gyroSensor->gyroDev); mpuResetFn = gyroSensor->gyroDev.mpuConfiguration.resetFn; // must be set after mpuDetect #endif diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 1bbb627a89..4387c872e3 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -53,6 +53,8 @@ typedef enum { GYRO_ICM20608G, GYRO_ICM20649, GYRO_ICM20689, + GYRO_ICM42605, + GYRO_ICM42688P, GYRO_BMI160, GYRO_IMUF9001, GYRO_FAKE diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h index 2345ab8aba..426ec9b767 100644 --- a/src/main/target/common_fc_pre.h +++ b/src/main/target/common_fc_pre.h @@ -228,3 +228,6 @@ #define USE_CMS_FAILSAFE_MENU #define USE_CMS_GPS_RESCUE_MENU #endif + +// ICM42688P define +#define USE_GYRO_DLPF_EXPERIMENTAL From c9cb676f1ed13222e80e7ee8dc00b65cb806b489 Mon Sep 17 00:00:00 2001 From: Roland <28628457+Peck07@users.noreply.github.com> Date: Fri, 2 Jun 2023 14:39:00 +0200 Subject: [PATCH 09/37] add ICM42688P support to FLYWOOF411_5IN1_AIO target (#907) add ICM426xx support to FLYWOOF411_5IN1_AIO target --- src/main/target/FLYWOOF411_5IN1_AIO/target.h | 8 ++++++++ src/main/target/FLYWOOF411_5IN1_AIO/target.mk | 1 + 2 files changed, 9 insertions(+) diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.h b/src/main/target/FLYWOOF411_5IN1_AIO/target.h index c3cf698af1..fc3d6d1f90 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.h +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.h @@ -61,6 +61,14 @@ //#define USE_ACC_SPI_ICM20689 //#define ACC_ICM20689_ALIGN CW180_DEG +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P + +#define ICM42688P_SPI_INSTANCE SPI1 +#define ICM42688P_CS_PIN PB2 +#define ACC_ICM426XX_ALIGN CW90_DEG +#define GYRO_ICM426XX_ALIGN CW90_DEG + // *************** Baro ************************** #define USE_I2C diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk index d6dc58877c..19d3a639b7 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk @@ -6,6 +6,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ From 9c0d7044e2c0bf614da0df859ade25676cb0bdd8 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 14 Jun 2023 10:36:17 -0500 Subject: [PATCH 10/37] bugfix gating USE_GYRO_DATA_ANALYSE (#917) bugfix gating USE_GYRO_DATA_ANALYSE when is used --- src/main/flight/pid.c | 4 +++- src/main/sensors/gyro.h | 2 ++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 2344beb3d5..19b51d18f7 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -315,12 +315,14 @@ void pidInitFilters(const pidProfile_t *pidProfile) { dtermABGapplyFn = (filterApplyFnPtr)alphaBetaGammaApply; ABGInit(&dtermABG[axis], pidProfile->dterm_ABG_alpha, pidProfile->dterm_ABG_boost, pidProfile->dterm_ABG_half_life, dT); } - +#ifdef USE_GYRO_DATA_ANALYSE if (isDynamicFilterActive()) { for (int axis2 = 0; axis2 < gyroConfig()->dyn_notch_count; axis2++) { biquadFilterInit(&dtermNotch[axis][axis2], 400, targetPidLooptime, gyroConfig()->dyn_notch_q / 100.0f, FILTER_NOTCH); } } +#endif + } #if defined(USE_THROTTLE_BOOST) diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 4387c872e3..0f32c699e1 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -198,7 +198,9 @@ bool gyroYawSpinDetected(void); uint16_t gyroAbsRateDps(int axis); uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg); float applySmithPredictor(smithPredictor_t *smithPredictor, float gyroFiltered); +#ifdef USE_GYRO_DATA_ANALYSE bool isDynamicFilterActive(void); +#endif #ifdef USE_YAW_SPIN_RECOVERY void initYawSpinRecovery(int maxYawRate); #endif From a0b59bba2b204e301b10d3aa8abcb95b48de27d4 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Fri, 30 Jun 2023 11:06:54 -0500 Subject: [PATCH 11/37] [Target] fix FLYWOOF411_5IN1_AIO ICM42688P alignment (#911) fix FLYWOOF411_5IN1_AIO ICM42688P align --- src/main/target/FLYWOOF411_5IN1_AIO/target.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.h b/src/main/target/FLYWOOF411_5IN1_AIO/target.h index fc3d6d1f90..5e93cd6460 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.h +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.h @@ -66,8 +66,8 @@ #define ICM42688P_SPI_INSTANCE SPI1 #define ICM42688P_CS_PIN PB2 -#define ACC_ICM426XX_ALIGN CW90_DEG -#define GYRO_ICM426XX_ALIGN CW90_DEG +#define ACC_ICM42688P_ALIGN CW0_DEG_FLIP +#define GYRO_ICM42688P_ALIGN CW0_DEG_FLIP // *************** Baro ************************** #define USE_I2C From f25f0494a7fa07a8f028d642483e9053116e7926 Mon Sep 17 00:00:00 2001 From: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> Date: Wed, 12 Jul 2023 11:03:18 -0500 Subject: [PATCH 12/37] [Target] IFLIGHT_F745_AIO_V2 (MPU6000 Only) (#895) * IFLIGHT_F745_AIO_V2 (MPU6000 ONLY) TARGET * IFLIGHT_F745_AIO_V2 - target.mk replace tabs w/ spaces --- src/main/target/IFLIGHT_F745_AIO_V2/target.c | 44 ++++ src/main/target/IFLIGHT_F745_AIO_V2/target.h | 188 ++++++++++++++++++ src/main/target/IFLIGHT_F745_AIO_V2/target.mk | 15 ++ 3 files changed, 247 insertions(+) create mode 100644 src/main/target/IFLIGHT_F745_AIO_V2/target.c create mode 100644 src/main/target/IFLIGHT_F745_AIO_V2/target.h create mode 100644 src/main/target/IFLIGHT_F745_AIO_V2/target.mk diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.c b/src/main/target/IFLIGHT_F745_AIO_V2/target.c new file mode 100644 index 0000000000..c57c497050 --- /dev/null +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.c @@ -0,0 +1,44 @@ +/* + * 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/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0 ), //LED + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0 ), //CAM + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0 ), // M3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0 ), // M4 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR, 0, 0 ), // M5 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR, 0, 0 ), // M6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1 ), // M7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // M8 + + }; diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.h b/src/main/target/IFLIGHT_F745_AIO_V2/target.h new file mode 100644 index 0000000000..6eec787ed9 --- /dev/null +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.h @@ -0,0 +1,188 @@ +/* + * 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 + +#define TARGET_BOARD_IDENTIFIER "IFRC" + +#define USBD_PRODUCT_STRING "IFLIGHT_F745_AIO_V2" + +#define ENABLE_DSHOT_DMAR true + +#define LED0_PIN PC13 + +#define USE_BEEPER +#define BEEPER_PIN PD2 +#define BEEPER_INVERTED + +//**********Gyro Acc *************// + +#define USE_ACC +#define USE_GYRO +#define USE_DUAL_GYRO + +#define USE_SPI_GYRO +//#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 + +#define USE_EXTI +#define USE_GYRO_EXTI +#define GYRO_1_EXTI_PIN PD0 +#define GYRO_2_EXTI_PIN PD8 +#define MPU_INT_EXTI + +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define GYRO_2_CS_PIN PB12 +#define GYRO_2_SPI_INSTANCE SPI2 + +#define GYRO_1_ALIGN CW0_DEG +#define ACC_1_ALIGN CW0_DEG +#define GYRO_2_ALIGN CW180_DEG +#define ACC_2_ALIGN CW180_DEG + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW +#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 + +//**********Mag and Baro**********// + +#define USE_MAG +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define MAG_HMC5883_ALIGN CW180_DEG +#define MAG_QMC5883_ALIGN CW180_DEG +#define MAG_I2C_INSTANCE (I2CDEV_1) + +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define BARO_I2C_INSTANCE (I2CDEV_1) + +//**********Serial****************// + +#define USE_VCP +//#define USE_USB_DETECT +//#define USB_DETECT_PIN PC4 + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define USE_UART7 +#define UART7_RX_PIN PE7 +#define UART7_TX_PIN PE8 + +#define USE_UART8 +#define UART8_RX_PIN PE0 +#define UART8_TX_PIN PE1 + +#define SERIAL_PORT_COUNT 8 //VCP, USART1, USART2, USART3, UART4, USART6, USART7, USART8 + +#define USE_ESCSERIAL +#define USE_CAMERA_CONTROL +#define CAMERA_CONTROL_PIN PB3 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI4 +#define MAX7456_SPI_CS_PIN PE4 +#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz +#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define FLASH_CS_PIN PA15 +#define FLASH_SPI_INSTANCE SPI3 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE_1 (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_I2C_DEVICE_2 +#define I2C_DEVICE_2 (I2CDEV_2) +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_ADC +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PC5 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define CURRENT_METER_SCALE_DEFAULT 100 + +#define USE_LED_STRIP + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY ) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#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 USABLE_TIMER_CHANNEL_COUNT 10 + +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.mk b/src/main/target/IFLIGHT_F745_AIO_V2/target.mk new file mode 100644 index 0000000000..525f68127c --- /dev/null +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.mk @@ -0,0 +1,15 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_hal.c \ + drivers/max7456.c From 75b47d1591249f40f1f9c0fa5aa2422f7a7d9997 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 23 Aug 2023 11:34:21 -0500 Subject: [PATCH 13/37] [Target] JHEF7DUAL add ICM42688P (#902) add ICM42688P to JHEF7DUAL --- src/main/target/JHEF7DUAL/target.h | 7 ++++++- src/main/target/JHEF7DUAL/target.mk | 1 + 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/target/JHEF7DUAL/target.h b/src/main/target/JHEF7DUAL/target.h index e7e4e5c221..1545a2a13c 100644 --- a/src/main/target/JHEF7DUAL/target.h +++ b/src/main/target/JHEF7DUAL/target.h @@ -53,10 +53,12 @@ #define USE_GYRO #define USE_GYRO_SPI_MPU6000 #define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_ICM42688P #define USE_ACC #define USE_ACC_SPI_MPU6000 #define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_ICM42688P #define ACC_ICM20689_1_ALIGN CW90_DEG #define GYRO_ICM20689_1_ALIGN CW90_DEG @@ -68,6 +70,9 @@ #define GYRO_2_ALIGN GYRO_MPU6000_2_ALIGN #define ACC_2_ALIGN ACC_MPU6000_2_ALIGN +#define ACC_ICM42688P_ALIGN CW90_DEG +#define GYRO_ICM42688P_ALIGN CW90_DEG + #define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 // *************** Baro ************************** @@ -140,7 +145,7 @@ #define USE_ADC #define ADC_INSTANCE ADC3 -#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2 +#define ADC3_DMA_OPT 0 // DMA 2 Stream 0 Channel 2 #define CURRENT_METER_ADC_PIN PC1 #define VBAT_ADC_PIN PC2 diff --git a/src/main/target/JHEF7DUAL/target.mk b/src/main/target/JHEF7DUAL/target.mk index 8b16c3f1b2..42e86d325d 100644 --- a/src/main/target/JHEF7DUAL/target.mk +++ b/src/main/target/JHEF7DUAL/target.mk @@ -5,6 +5,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_fake.c \ drivers/light_ws2811strip.c \ From b54d768a99a0ab8a4b4474e3682445fc726a9379 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 23 Aug 2023 11:44:33 -0500 Subject: [PATCH 14/37] [Target] GEPRC_F722_AIO ICM42688P (#903) * GEPRC_F722_AIO ICM42688P Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> --- src/main/target/GEPRC_F722_AIO/target.c | 45 +++++++ src/main/target/GEPRC_F722_AIO/target.h | 158 +++++++++++++++++++++++ src/main/target/GEPRC_F722_AIO/target.mk | 15 +++ 3 files changed, 218 insertions(+) create mode 100644 src/main/target/GEPRC_F722_AIO/target.c create mode 100644 src/main/target/GEPRC_F722_AIO/target.h create mode 100644 src/main/target/GEPRC_F722_AIO/target.mk diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c new file mode 100644 index 0000000000..5fdda10d02 --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/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/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { +DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //CAMERA CONTROL +DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), //PPM + +DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //MOTOR 1 +DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), //MOTOR 2 +DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), //MOTOR 3 +DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), //MOTOR 4 + +//DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), //in config but match no pins +//DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), //pretty sure left over from +//DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), //geprc_f722_bthd target/config +//DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), //as match motors 5-8 + +DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0) //LED +}; diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h new file mode 100644 index 0000000000..2cb368bae7 --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -0,0 +1,158 @@ +/* + * 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 . + * + * Prepared by Kaio + */ +#pragma once + +#define TARGET_BOARD_IDENTIFIER "S7X2" +#define USBD_PRODUCT_STRING "GEPRC_F722_AIO" +#define TARGET_MANUFACTURER_IDENTIFIER "GEPR" + +#define LED0_PIN PC4 + +#define USE_BEEPER +#define BEEPER_PIN PC15 +#define BEEPER_INVERTED + +#define ENABLE_DSHOT_DMAR true + +#define USE_EXTI +#define MPU_INT_EXTI PA8 +#define USE_MPU_DATA_READY_SIGNAL + +#define USE_GYRO + +#define USE_GYRO_SPI_ICM42688P +#define ICM42688P_CS_PIN PA15 +#define ICM42688P_SPI_INSTANCE SPI1 +#define GYRO_ICM42688P_ALIGN CW90_DEG + +#define USE_GYRO_SPI_MPU6000 +#define MPU6000_CS_PIN PA15 +#define MPU6000_SPI_INSTANCE SPI1 +#define GYRO_MPU6000_ALIGN CW90_DEG + +#define USE_ACC + +#define USE_ACC_SPI_ICM42688P +#define ACC_ICM42688P_ALIGN CW90_DEG + +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6000_ALIGN CW90_DEG + +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_BMP085 +#define USE_BARO_MS5611 +#define BARO_I2C_INSTANCE (I2CDEV_2) + +#define USE_MAG +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define MAG_I2C_INSTANCE (I2CDEV_2) + +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN PB12 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define FLASH_SPI_INSTANCE SPI3 +#define FLASH_CS_PIN PB9 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_VCP +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 //USB + 5 UARTS + +#define USE_ESCSERIAL //PPM +#define ESCSERIAL_TIMER_TX_PIN PA3 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +//#define USE_I2C +//#define USE_I2C_DEVICE_1 +//#define I2C1_SCL PB8 +//#define I2C1_SDA PB9 +//#define I2C_DEVICE (I2CDEV_1) + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +#define I2C_DEVICE (I2CDEV_2) + +#define USE_ADC +#define ADC3_DMA_STREAM DMA2_Stream0 +#define VBAT_ADC_PIN PC2 +#define CURRENT_METER_ADC_PIN PC1 +//#define RSSI_ADC_PIN PC2 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define CURRENT_METER_SCALE_DEFAULT 100 + +#define SERIALRX_PROVIDER SERIALRX_SBUS +//#define SERIALRX_UART SERIAL_PORT_USART2 + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES ( FEATURE_OSD | FEATURE_TELEMETRY ) + +#define TARGET_IO_PORTA ( 0xffff ) +#define TARGET_IO_PORTB ( 0xffff ) +#define TARGET_IO_PORTC ( 0xffff ) +#define TARGET_IO_PORTD ( 0xffff ) + +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(2) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/GEPRC_F722_AIO/target.mk b/src/main/target/GEPRC_F722_AIO/target.mk new file mode 100644 index 0000000000..ed078d59ff --- /dev/null +++ b/src/main/target/GEPRC_F722_AIO/target.mk @@ -0,0 +1,15 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_icm426xx.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/max7456.c\ + drivers/light_ws2811strip.c From 11d38e5a06dee654f359d5681b4c4473b4e22b92 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 23 Aug 2023 13:00:18 -0500 Subject: [PATCH 15/37] [Target] RUSHBLADEF7HD add ICM42688P (#904) * RUSHBLADEF7HD; ICM42688P, MPU6000 --- .../target.c | 0 src/main/target/RUSHBLADEF7HD/target.h | 156 ++++++++++++++++++ src/main/target/RUSHBLADEF7HD/target.mk | 12 ++ src/main/target/RUSH_BLADE_F7_HD/target.h | 151 ----------------- src/main/target/RUSH_BLADE_F7_HD/target.mk | 11 -- 5 files changed, 168 insertions(+), 162 deletions(-) rename src/main/target/{RUSH_BLADE_F7_HD => RUSHBLADEF7HD}/target.c (100%) create mode 100644 src/main/target/RUSHBLADEF7HD/target.h create mode 100644 src/main/target/RUSHBLADEF7HD/target.mk delete mode 100644 src/main/target/RUSH_BLADE_F7_HD/target.h delete mode 100644 src/main/target/RUSH_BLADE_F7_HD/target.mk diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.c b/src/main/target/RUSHBLADEF7HD/target.c similarity index 100% rename from src/main/target/RUSH_BLADE_F7_HD/target.c rename to src/main/target/RUSHBLADEF7HD/target.c diff --git a/src/main/target/RUSHBLADEF7HD/target.h b/src/main/target/RUSHBLADEF7HD/target.h new file mode 100644 index 0000000000..3041655e66 --- /dev/null +++ b/src/main/target/RUSHBLADEF7HD/target.h @@ -0,0 +1,156 @@ +/* +* 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 +//#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "RUSH" +#define USBD_PRODUCT_STRING "BLADE_F7_HD" + +#define ENABLE_DSHOT_DMAR true + +#define USE_LED_STRIP + +#define LED0_PIN PB10 + +#define USE_BEEPER +#define BEEPER_PIN PB2 +#define BEEPER_INVERTED + + +// *************** SPI1 Gyro & ACC ******************* + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_EXTI +#define USE_GYRO +#define USE_ACC + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define MPU6000_CS_PIN PC4 +#define MPU_INT_EXTI PA4 +#define MPU6000_SPI_INSTANCE SPI1 +#define GYRO_MPU6000_ALIGN CW270_DEG +#define ACC_MPU6000_ALIGN CW270_DEG + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define ICM42688P_EXTI_PIN PA4 +#define ICM42688P_CS_PIN PC4 +#define ICM42688P_SPI_INSTANCE SPI1 +#define GYRO_ICM42688P_ALIGN CW270_DEG +#define ACC_ICM42688P_ALIGN CW270_DEG + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +// *************** I2C /Baro/Mag ********************* + +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE_1 (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define BARO_I2C_INSTANCE (I2CDEV_1) +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 + +//#define MAG_I2C_INSTANCE (I2CDEV_1) +//#define USE_MAG +//#define USE_MAG_HMC5883 +//#define USE_MAG_QMC5883 + +// *************** SPI3 BLACKBOX**************** + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define FLASH_CS_PIN PB12 +#define FLASH_SPI_INSTANCE SPI2 + +// *************** UART ***************************** + +#define USE_VCP +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +//#define ADC1_DMA_STREAM DMA2_Stream0 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +//#define RSSI_ADC_PIN PC1 + +// *************** Others *************************** + + +#define DEFAULT_FEATURES ( FEATURE_TELEMETRY ) +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define CURRENT_METER_SCALE_DEFAULT 179 + +#define USE_ESCSERIAL + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define USABLE_TIMER_CHANNEL_COUNT 10 +#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)) diff --git a/src/main/target/RUSHBLADEF7HD/target.mk b/src/main/target/RUSHBLADEF7HD/target.mk new file mode 100644 index 0000000000..4a0083c78c --- /dev/null +++ b/src/main/target/RUSHBLADEF7HD/target.mk @@ -0,0 +1,12 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_mpu6000.c \ +drivers/accgyro/accgyro_spi_icm426xx.c \ +drivers/barometer/barometer_ms5611.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/barometer/barometer_bmp085.c \ +drivers/light_ws2811strip.c \ +drivers/max7456.c diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.h b/src/main/target/RUSH_BLADE_F7_HD/target.h deleted file mode 100644 index 1ad1a5f0c1..0000000000 --- a/src/main/target/RUSH_BLADE_F7_HD/target.h +++ /dev/null @@ -1,151 +0,0 @@ -/* - * 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 - //#define USE_TARGET_CONFIG - - #define TARGET_BOARD_IDENTIFIER "RUSH" - #define USBD_PRODUCT_STRING "BLADE_F7_HD" - - #define ENABLE_DSHOT_DMAR true - - #define USE_LED_STRIP - - #define LED0_PIN PB10 - - #define USE_BEEPER - #define BEEPER_PIN PB2 - #define BEEPER_INVERTED - - - // *************** SPI1 Gyro & ACC ******************* - - #define USE_SPI - #define USE_SPI_DEVICE_1 - #define SPI1_SCK_PIN PA5 - #define SPI1_MISO_PIN PA6 - #define SPI1_MOSI_PIN PA7 - - #define USE_EXTI - #define MPU_INT_EXTI PA4 - - #define MPU6000_CS_PIN PC4 - #define MPU6000_SPI_INSTANCE SPI1 - - #define USE_GYRO - #define USE_GYRO_SPI_MPU6000 - - #define USE_ACC - #define USE_ACC_SPI_MPU6000 - - #define GYRO_MPU6000_ALIGN CW270_DEG - #define ACC_MPU6000_ALIGN CW270_DEG - - #define USE_MPU_DATA_READY_SIGNAL - #define ENSURE_MPU_DATA_READY_IS_LOW - - // *************** I2C /Baro/Mag ********************* - - #define USE_I2C - - #define USE_I2C_DEVICE_1 - #define I2C_DEVICE_1 (I2CDEV_1) - #define I2C1_SCL PB8 - #define I2C1_SDA PB9 - - #define BARO_I2C_INSTANCE (I2CDEV_1) - #define USE_BARO - #define USE_BARO_BMP280 - #define USE_BARO_MS5611 - #define USE_BARO_BMP085 - - //#define MAG_I2C_INSTANCE (I2CDEV_1) - //#define USE_MAG - //#define USE_MAG_HMC5883 - //#define USE_MAG_QMC5883 - - // *************** SPI3 BLACKBOX**************** - - #define USE_SPI_DEVICE_2 - #define SPI2_SCK_PIN PB13 - #define SPI2_MISO_PIN PB14 - #define SPI2_MOSI_PIN PB15 - - #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT - #define USE_FLASHFS - #define USE_FLASH_M25P16 - #define FLASH_CS_PIN PB12 - #define FLASH_SPI_INSTANCE SPI2 - - // *************** UART ***************************** - - #define USE_VCP - #define USE_USB_DETECT - - #define USE_UART1 - #define UART1_TX_PIN PA9 - #define UART1_RX_PIN PA10 - - #define USE_UART2 - #define UART2_TX_PIN PA2 - #define UART2_RX_PIN PA3 - - #define USE_UART3 - #define UART3_TX_PIN PC10 - #define UART3_RX_PIN PC11 - - #define USE_UART4 - #define UART4_TX_PIN PA0 - #define UART4_RX_PIN PA1 - - #define USE_UART5 - #define UART5_TX_PIN PC12 - #define UART5_RX_PIN PD2 - - #define SERIAL_PORT_COUNT 6 - - #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL - #define SERIALRX_PROVIDER SERIALRX_SBUS - #define SERIALRX_UART SERIAL_PORT_USART2 - - // *************** ADC ***************************** - #define USE_ADC - //#define ADC1_DMA_STREAM DMA2_Stream0 - #define VBAT_ADC_PIN PC0 - #define CURRENT_METER_ADC_PIN PC1 - //#define RSSI_ADC_PIN PC1 - - // *************** Others *************************** - - - #define DEFAULT_FEATURES ( FEATURE_TELEMETRY ) - #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC - #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - #define CURRENT_METER_SCALE_DEFAULT 179 - - #define USE_ESCSERIAL - - #define TARGET_IO_PORTA 0xffff - #define TARGET_IO_PORTB 0xffff - #define TARGET_IO_PORTC 0xffff - #define TARGET_IO_PORTD 0xffff - - #define USABLE_TIMER_CHANNEL_COUNT 10 - #define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)) diff --git a/src/main/target/RUSH_BLADE_F7_HD/target.mk b/src/main/target/RUSH_BLADE_F7_HD/target.mk deleted file mode 100644 index 3b2730cf37..0000000000 --- a/src/main/target/RUSH_BLADE_F7_HD/target.mk +++ /dev/null @@ -1,11 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c From 9d0485114d549d402e8e82535549902dc9029c9a Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 23 Aug 2023 15:06:20 -0500 Subject: [PATCH 16/37] [Target] BETAFPVF722 add ICM42688P; fix Timers (#905) BETAFPVF722 add ICM42688P; fix Timers Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> --- src/main/target/BETAFPVF722/target.c | 4 +--- src/main/target/BETAFPVF722/target.h | 17 ++++++++++++++--- src/main/target/BETAFPVF722/target.mk | 1 + 3 files changed, 16 insertions(+), 6 deletions(-) diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c index 1af98e92f5..b2aeb61ba6 100644 --- a/src/main/target/BETAFPVF722/target.c +++ b/src/main/target/BETAFPVF722/target.c @@ -28,8 +28,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION - DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL - + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2 DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3 @@ -38,5 +37,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5 - }; diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 31821bc7b2..595a08c5f2 100644 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -33,7 +33,7 @@ #define BEEPER_INVERTED //define camera control -#define CAMERA_CONTROL_PIN PC8 +// N/A //MPU-6000 #define USE_GYRO @@ -49,6 +49,16 @@ #define GYRO_MPU6000_ALIGN CW180_DEG #define ACC_MPU6000_ALIGN CW180_DEG + +// ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 +#define GYRO_ICM42688P_ALIGN CW180_DEG +#define ACC_ICM42688P_ALIGN CW180_DEG + + // OSD #define USE_MAX7456 #define MAX7456_SPI_INSTANCE SPI3 @@ -120,6 +130,7 @@ #define VBAT_ADC_PIN PC0 #define RSSI_ADC_PIN PC2 #define CURRENT_METER_SCALE_DEFAULT 450 // 3.3/120A = 25mv/A +#define USE_SERIAL_4WAY_BLHELI_INTERFACE // SPI devices #define USE_SPI @@ -154,5 +165,5 @@ #define TARGET_IO_PORTD (BIT(2)) // timers -#define USABLE_TIMER_CHANNEL_COUNT 8 -#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/BETAFPVF722/target.mk b/src/main/target/BETAFPVF722/target.mk index 56beeaedad..0da79a44b5 100644 --- a/src/main/target/BETAFPVF722/target.mk +++ b/src/main/target/BETAFPVF722/target.mk @@ -4,6 +4,7 @@ FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ From 43543b4de7d7e6e1f3b2d97d4f95bb5bf8583e7c Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 23 Aug 2023 15:52:56 -0500 Subject: [PATCH 17/37] [Target] JHEF411 - add ICM42688P (#925) JHEF411 - add ICM42688P --- src/main/target/JHEF411/target.h | 7 +++++++ src/main/target/JHEF411/target.mk | 1 + 2 files changed, 8 insertions(+) diff --git a/src/main/target/JHEF411/target.h b/src/main/target/JHEF411/target.h index f4c720412c..7db7a91a6d 100644 --- a/src/main/target/JHEF411/target.h +++ b/src/main/target/JHEF411/target.h @@ -56,6 +56,13 @@ #define USE_ACC #define USE_ACC_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG + +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 +#define ACC_ICM42688P_ALIGN CW180_DEG +#define GYRO_ICM42688P_ALIGN CW180_DEG // *************** Baro ************************** #define USE_I2C diff --git a/src/main/target/JHEF411/target.mk b/src/main/target/JHEF411/target.mk index a22931f0a8..04a1ea3283 100644 --- a/src/main/target/JHEF411/target.mk +++ b/src/main/target/JHEF411/target.mk @@ -4,6 +4,7 @@ FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ From 548e054af08b7baa048ca8670d94db22cd2f9bb1 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 24 Aug 2023 11:41:26 -0500 Subject: [PATCH 18/37] [Target Fix] MATEKF722SE - allow mpu6500 on gyro 1 and/or mpu6000 on gyro 2 (#928) [Target Fix] MATEKF722SE allow MPU6500 on gyro 1 and MPU6000 on gyro 2 --- src/main/target/MATEKF722SE/target.h | 14 +++++++++----- src/main/target/MATEKF722SE/target.mk | 1 + 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index df30407eda..dc89a9529d 100755 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -46,7 +46,7 @@ #define USE_EXTI #define GYRO_1_EXTI_PIN PC4 #define GYRO_2_EXTI_PIN PC3 -#define MPU_INT_EXTI +#define MPU_INT_EXTI PC4 #define GYRO_1_CS_PIN PB2 #define GYRO_1_SPI_INSTANCE SPI1 @@ -61,15 +61,19 @@ #define USE_ACC_SPI_MPU6000 #define USE_ACC_SPI_MPU6500 +#define GYRO_1_ALIGN CW180_DEG_FLIP +#define ACC_1_ALIGN CW180_DEG_FLIP #define GYRO_MPU6000_1_ALIGN CW180_DEG_FLIP #define ACC_MPU6000_1_ALIGN CW180_DEG_FLIP -#define GYRO_1_ALIGN GYRO_MPU6000_1_ALIGN -#define ACC_1_ALIGN ACC_MPU6000_1_ALIGN +#define GYRO_MPU6500_1_ALIGN CW180_DEG_FLIP +#define ACC_MPU6500_1_ALIGN CW180_DEG_FLIP +#define GYRO_2_ALIGN CW90_DEG +#define ACC_2_ALIGN CW90_DEG #define GYRO_MPU6500_2_ALIGN CW90_DEG #define ACC_MPU6500_2_ALIGN CW90_DEG -#define GYRO_2_ALIGN GYRO_MPU6500_2_ALIGN -#define ACC_2_ALIGN ACC_MPU6500_2_ALIGN +#define GYRO_MPU6000_2_ALIGN CW90_DEG +#define ACC_MPU6000_2_ALIGN CW90_DEG #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW diff --git a/src/main/target/MATEKF722SE/target.mk b/src/main/target/MATEKF722SE/target.mk index db67145925..cd0322069a 100755 --- a/src/main/target/MATEKF722SE/target.mk +++ b/src/main/target/MATEKF722SE/target.mk @@ -3,6 +3,7 @@ FEATURES += VCP ONBOARDFLASH SDCARD TARGET_SRC = \ + drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ From 9d64ef641d7713ec5e84c66552dd36db809133dc Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 24 Aug 2023 11:49:49 -0500 Subject: [PATCH 19/37] [Target] DIAT_MAMBAF405_2022B - MPU6000, MPU6500, ICM42688P (#908) [Target] DIAT_MAMBAF405_2022B - MPU6000, MPU6500, ICM42688P --- src/main/target/DIAT_MAMBAF405_2022B/target.c | 41 +++++ src/main/target/DIAT_MAMBAF405_2022B/target.h | 164 ++++++++++++++++++ .../target/DIAT_MAMBAF405_2022B/target.mk | 16 ++ 3 files changed, 221 insertions(+) create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.c create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.h create mode 100644 src/main/target/DIAT_MAMBAF405_2022B/target.mk diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.c b/src/main/target/DIAT_MAMBAF405_2022B/target.c new file mode 100644 index 0000000000..37e46483ec --- /dev/null +++ b/src/main/target/DIAT_MAMBAF405_2022B/target.c @@ -0,0 +1,41 @@ +/* + * This file is part of EmuFlight. It is derived from Betaflight. + * + * This is 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. + * + * This software 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 software. + * + * If not, see . + */ + +#include +#include "platform.h" +#include "drivers/io.h" +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP, + DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight, + DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // baro/mag // no dps310 in EmuFlight, + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0 ), // M1 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0 ), // M2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // M3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), // M4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // M5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // M6 +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.h b/src/main/target/DIAT_MAMBAF405_2022B/target.h new file mode 100644 index 0000000000..2e8faaa864 --- /dev/null +++ b/src/main/target/DIAT_MAMBAF405_2022B/target.h @@ -0,0 +1,164 @@ +/* + * This file is part of EmuFlight. It is derived from Betaflight. + * + * This is 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. + * + * This software 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 software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "DIAT" +#define USBD_PRODUCT_STRING "MAMBAF405_2022B" + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 +#define USE_BARO +#define USE_ADC +#define USE_SPI_GYRO + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 //testing +#define USE_FLASH_W25M //testing +#define USE_FLASH_W25M512 //testing +#define USE_FLASH_W25Q //testing +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC15 +#define LED1_PIN PC14 +#define LED_STRIP_PIN PB3 +#define USE_BEEPER +#define BEEPER_PIN PC13 +#define BEEPER_INVERTED + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +#define MPU_INT_EXTI PC4 + +#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC_MPU6500_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define ACC_ICM42688P_ALIGN CW270_DEG +#define GYRO_ICM42688P_ALIGN CW270_DEG +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 + +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE (I2CDEV_1) +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define BARO_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 +// notice - this file was programmatically generated and likely needs MAG/BARO manually added and/or verified. + +#define FLASH_CS_PIN PA15 +#define FLASH_SPI_INSTANCE SPI3 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_INSTANCE SPI2 + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define UART1_TX_PIN PB6 +#define UART2_TX_PIN PA2 +#define UART3_TX_PIN PB10 +#define UART4_TX_PIN PA0 +#define UART5_TX_PIN PC12 +#define UART6_TX_PIN PC6 +#define UART1_RX_PIN PB7 +#define UART2_RX_PIN PA3 +#define UART3_RX_PIN PB11 +#define UART4_RX_PIN PA1 +#define UART5_RX_PIN PD2 +#define UART6_RX_PIN PC7 +#define INVERTER_PIN_UART1 PC0 +#define SERIAL_PORT_COUNT 7 +// notice - UART/USART were programmatically generated + +#define VBAT_ADC_PIN PC1 +#define CURRENT_METER_ADC_PIN PC3 +#define ADC3_DMA_STREAM DMA2_Stream0 // # ADC 3: DMA2 Stream 0 Channel 2 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define DEFAULT_CURRENT_METER_SCALE 183 +#define ADC_INSTANCE ADC3 +// notice - DMA conversion were programmatically generated and may be incomplete. + +#define ENABLE_DSHOT_DMAR true + +#define PINIO1_PIN PC2 +#define PINIO2_PIN PC5 +#define PINIO1_CONFIG 129 +#define PINIO2_CONFIG 129 +#define PINIO1_BOX 0 +#define PINIO2_BOX 40 +// notice - this file was programmatically generated and may not have accounted for any config instance of "#define TLM_INVERTED ON", etc. + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2)) + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +// notice - incomplete; may need additional DEFAULT_FEATURES; e.g. FEATURE_SOFTSERIAL | FEATURE_RX_SPI + +#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(11) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.mk b/src/main/target/DIAT_MAMBAF405_2022B/target.mk new file mode 100644 index 0000000000..775a554519 --- /dev/null +++ b/src/main/target/DIAT_MAMBAF405_2022B/target.mk @@ -0,0 +1,16 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_mpu6000.c \ +drivers/accgyro/accgyro_mpu6500.c \ +drivers/accgyro/accgyro_spi_mpu6500.c \ +drivers/accgyro/accgyro_spi_icm426xx.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ + +# notice - this file was programmatically generated and may be incomplete. +# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc. From 41cfd39355b2dcc67f4a7883a3dccaf1ca5e044f Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 11 Oct 2023 14:04:14 -0500 Subject: [PATCH 20/37] add rc rates_type to BBL header (#931) --- src/main/blackbox/blackbox.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8ee2428c8d..b17ed12485 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1138,6 +1138,7 @@ static bool blackboxWriteSysinfo(void) { BLACKBOX_PRINT_HEADER_LINE("spa_yaw_p", "%d", currentPidProfile->setPointPTransition[YAW]); BLACKBOX_PRINT_HEADER_LINE("spa_yaw_i", "%d", currentPidProfile->setPointITransition[YAW]); BLACKBOX_PRINT_HEADER_LINE("spa_yaw_d", "%d", currentPidProfile->setPointDTransition[YAW]); + BLACKBOX_PRINT_HEADER_LINE("rates_type", "%d", currentControlRateProfile->rates_type); BLACKBOX_PRINT_HEADER_LINE("rc_rates", "%d,%d,%d", currentControlRateProfile->rcRates[ROLL], currentControlRateProfile->rcRates[PITCH], currentControlRateProfile->rcRates[YAW]); From c55b0d708bcd9d4d127a8ae5523861bddbadf5c3 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 11 Oct 2023 14:05:21 -0500 Subject: [PATCH 21/37] add motor_poles to BBL header (#932) * add motor_poles to BBL header --- src/main/blackbox/blackbox.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index b17ed12485..5797c373a8 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1267,6 +1267,7 @@ static bool blackboxWriteSysinfo(void) { BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->dev.motorPwmProtocol); BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->dev.motorPwmRate); BLACKBOX_PRINT_HEADER_LINE("dshot_idle_value", "%d", motorConfig()->digitalIdleOffsetValue); + BLACKBOX_PRINT_HEADER_LINE("motor_poles", "%d", motorConfig()->motorPoleCount); BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode); BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures); #ifdef USE_RC_SMOOTHING_FILTER From 6ba54464405346ac88ab9376e8f603129c973fa0 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 25 Oct 2023 15:17:08 -0500 Subject: [PATCH 22/37] option to apply dynamic-notches to RP vs normal/default RPY (#881) * add dynamicFilter mode. RP or RPY * dynamicFilter mode - OSD * dynamicFilter mode - rename mode to axis * dynamicFilter mode (axis) - #ifdef USE_GYRO_DATA_ANALYSE gating --- src/main/blackbox/blackbox.c | 3 +++ src/main/cms/cms_menu_imu.c | 27 ++++++++++++++++++++++++++- src/main/flight/pid.c | 4 +++- src/main/flight/pid.h | 2 ++ src/main/interface/msp.c | 24 ++++++++++++++++++++++++ src/main/interface/settings.c | 14 +++++++++++++- src/main/interface/settings.h | 3 +++ src/main/sensors/gyro.c | 8 +++++++- src/main/sensors/gyro.h | 10 ++++++++++ 9 files changed, 91 insertions(+), 4 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 5797c373a8..672d39fc3a 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1180,8 +1180,10 @@ static bool blackboxWriteSysinfo(void) { BLACKBOX_PRINT_HEADER_LINE("dterm_lowpass2_hz_roll", "%d", currentPidProfile->dFilter[ROLL].dLpf2); BLACKBOX_PRINT_HEADER_LINE("dterm_lowpass2_hz_pitch", "%d", currentPidProfile->dFilter[PITCH].dLpf2); BLACKBOX_PRINT_HEADER_LINE("dterm_lowpass2_hz_yaw", "%d", currentPidProfile->dFilter[YAW].dLpf2); +#ifdef USE_GYRO_DATA_ANALYSE BLACKBOX_PRINT_HEADER_LINE("dterm_dyn_notch_enable", "%d", currentPidProfile->dtermDynNotch); BLACKBOX_PRINT_HEADER_LINE("dterm_dyn_notch_q", "%d", currentPidProfile->dterm_dyn_notch_q); +#endif BLACKBOX_PRINT_HEADER_LINE("dterm_ABG_alpha", "%d", currentPidProfile->dterm_ABG_alpha); BLACKBOX_PRINT_HEADER_LINE("dterm_ABG_boost", "%d", currentPidProfile->dterm_ABG_boost); BLACKBOX_PRINT_HEADER_LINE("dterm_ABG_half_life", "%d", currentPidProfile->dterm_ABG_half_life); @@ -1240,6 +1242,7 @@ static bool blackboxWriteSysinfo(void) { BLACKBOX_PRINT_HEADER_LINE("dynamic_gyro_notch_count", "%d", gyroConfig()->dyn_notch_count); BLACKBOX_PRINT_HEADER_LINE("dynamic_gyro_notch_min_hz", "%d", gyroConfig()->dyn_notch_min_hz); BLACKBOX_PRINT_HEADER_LINE("dynamic_gyro_notch_max_hz", "%d", gyroConfig()->dyn_notch_max_hz); + BLACKBOX_PRINT_HEADER_LINE("dynamic_gyro_notch_axis", "%d", gyroConfig()->dyn_notch_axis); #endif BLACKBOX_PRINT_HEADER_LINE("gyro_ABG_alpha", "%d", gyroConfig()->gyro_ABG_alpha); BLACKBOX_PRINT_HEADER_LINE("gyro_ABG_boost", "%d", gyroConfig()->gyro_ABG_boost); diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index a8f3804735..e479a1fa17 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -104,6 +104,12 @@ static const char * const cms_FilterType[] = { "PT1", "BIQUAD", "PT2", "PT3", "PT4", }; +#ifdef USE_GYRO_DATA_ANALYSE +static const char * const cms_dynNotchAxisType[] = { + "RP", "RPY" +}; +#endif + static long cmsx_menuImu_onEnter(void) { pidProfileIndex = getCurrentPidProfileIndex(); tmpPidProfileIndex = pidProfileIndex + 1; @@ -490,10 +496,13 @@ static uint16_t gyroConfig_gyro_lowpass_hz_yaw; static uint16_t gyroConfig_gyro_lowpass2_hz_roll; static uint16_t gyroConfig_gyro_lowpass2_hz_pitch; static uint16_t gyroConfig_gyro_lowpass2_hz_yaw; +#ifdef USE_GYRO_DATA_ANALYSE static uint16_t gyroConfig_gyro_q; static uint8_t gyroConfig_gyro_notch_count; static uint16_t gyroConfig_gyro_notch_min_hz; static uint16_t gyroConfig_gyro_notch_max_hz; +static uint8_t gyroConfig_gyro_notch_axis; +#endif static uint16_t gyroConfig_gyro_abg_alpha; static uint16_t gyroConfig_gyro_abg_boost; static uint8_t gyroConfig_gyro_abg_half_life; @@ -518,14 +527,16 @@ static long cmsx_menuGyro_onEnter(void) { gyroConfig_gyro_lowpass2_hz_roll = gyroConfig()->gyro_lowpass2_hz[ROLL]; gyroConfig_gyro_lowpass2_hz_pitch = gyroConfig()->gyro_lowpass2_hz[PITCH]; gyroConfig_gyro_lowpass2_hz_yaw = gyroConfig()->gyro_lowpass2_hz[YAW]; +#ifdef USE_GYRO_DATA_ANALYSE gyroConfig_gyro_q = gyroConfig()->dyn_notch_q; gyroConfig_gyro_notch_count = gyroConfig()->dyn_notch_count; gyroConfig_gyro_notch_min_hz = gyroConfig()->dyn_notch_min_hz; gyroConfig_gyro_notch_max_hz = gyroConfig()->dyn_notch_max_hz; + gyroConfig_gyro_notch_axis = gyroConfig()->dyn_notch_axis; +#endif gyroConfig_gyro_abg_alpha = gyroConfig()->gyro_ABG_alpha; gyroConfig_gyro_abg_boost = gyroConfig()->gyro_ABG_boost; gyroConfig_gyro_abg_half_life = gyroConfig()->gyro_ABG_half_life; - #ifndef USE_GYRO_IMUF9001 gyroConfig_imuf_roll_q = gyroConfig()->imuf_roll_q; gyroConfig_imuf_pitch_q = gyroConfig()->imuf_pitch_q; @@ -550,10 +561,13 @@ static long cmsx_menuGyro_onExit(const OSD_Entry *self) { gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = gyroConfig_gyro_lowpass2_hz_roll; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = gyroConfig_gyro_lowpass2_hz_pitch; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = gyroConfig_gyro_lowpass2_hz_yaw; +#ifdef USE_GYRO_DATA_ANALYSE gyroConfigMutable()->dyn_notch_q = gyroConfig_gyro_q; gyroConfigMutable()->dyn_notch_count = gyroConfig_gyro_notch_count; gyroConfigMutable()->dyn_notch_min_hz = gyroConfig_gyro_notch_min_hz; gyroConfigMutable()->dyn_notch_max_hz = gyroConfig_gyro_notch_max_hz; + gyroConfigMutable()->dyn_notch_axis = gyroConfig_gyro_notch_axis; +#endif gyroConfigMutable()->gyro_ABG_alpha = gyroConfig_gyro_abg_alpha; gyroConfigMutable()->gyro_ABG_boost = gyroConfig_gyro_abg_boost; gyroConfigMutable()->gyro_ABG_half_life = gyroConfig_gyro_abg_half_life; @@ -584,10 +598,13 @@ static OSD_Entry cmsx_menuFilterGlobalEntries[] = { { "GYRO LPF2 PITCH", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass2_hz_pitch, 0, 16000, 1 }, 0 }, { "GYRO LPF2 YAW", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass2_hz_yaw, 0, 16000, 1 }, 0 }, #endif +#ifdef USE_GYRO_DATA_ANALYSE { "DYN NOTCH Q", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_q, 0, 1000, 1 }, 0 }, { "DYN NOTCH COUNT", OME_UINT8, NULL, &(OSD_UINT8_t) { &gyroConfig_gyro_notch_count, 1, 5, 1 }, 0 }, { "DYN NOTCH MIN HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_notch_min_hz, 30, 1000, 1 }, 0 }, { "DYN NOTCH MAX HZ", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_notch_max_hz, 200, 1000, 1 }, 0 }, + { "DYN NOTCH AXIS", OME_TAB, NULL, &(OSD_TAB_t) { (uint8_t *) &gyroConfig_gyro_notch_axis, 1, cms_dynNotchAxisType }, 0 }, +#endif #ifndef USE_GYRO_IMUF9001 { "IMUF W", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_imuf_w, 0, 512, 1 }, 0 }, { "ROLL Q", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_imuf_roll_q, 100, 16000, 100 }, 0 }, @@ -709,8 +726,10 @@ static uint16_t cmsx_dterm_lowpass2_type; static uint16_t cmsx_dterm_lowpass2_hz_roll; static uint16_t cmsx_dterm_lowpass2_hz_pitch; static uint16_t cmsx_dterm_lowpass2_hz_yaw; +#ifdef USE_GYRO_DATA_ANALYSE static uint8_t cmsx_dterm_dyn_notch_enable ; static uint16_t cmsx_dterm_dyn_notch_q; +#endif static uint16_t cmsx_dterm_abg_alpha; static uint16_t cmsx_dterm_abg_boost; static uint8_t cmsx_dterm_abg_half_life; @@ -725,8 +744,10 @@ static long cmsx_FilterPerProfileRead(void) { cmsx_dterm_lowpass2_hz_roll = pidProfile->dFilter[ROLL].dLpf2; cmsx_dterm_lowpass2_hz_pitch = pidProfile->dFilter[PITCH].dLpf2; cmsx_dterm_lowpass2_hz_yaw = pidProfile->dFilter[YAW].dLpf2; +#ifdef USE_GYRO_DATA_ANALYSE cmsx_dterm_dyn_notch_enable = pidProfile->dtermDynNotch; cmsx_dterm_dyn_notch_q = pidProfile->dterm_dyn_notch_q; +#endif cmsx_dterm_abg_alpha = pidProfile->dterm_ABG_alpha; cmsx_dterm_abg_boost = pidProfile->dterm_ABG_boost; cmsx_dterm_abg_half_life = pidProfile->dterm_ABG_half_life; @@ -744,8 +765,10 @@ static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self) { pidProfile->dFilter[ROLL].dLpf2 = cmsx_dterm_lowpass2_hz_roll; pidProfile->dFilter[PITCH].dLpf2 = cmsx_dterm_lowpass2_hz_pitch; pidProfile->dFilter[YAW].dLpf2 = cmsx_dterm_lowpass2_hz_yaw; +#ifdef USE_GYRO_DATA_ANALYSE pidProfile->dtermDynNotch = cmsx_dterm_dyn_notch_enable; pidProfile->dterm_dyn_notch_q = cmsx_dterm_dyn_notch_q; +#endif pidProfile->dterm_ABG_alpha = cmsx_dterm_abg_alpha; pidProfile->dterm_ABG_boost = cmsx_dterm_abg_boost; pidProfile->dterm_ABG_half_life = cmsx_dterm_abg_half_life; @@ -763,8 +786,10 @@ static OSD_Entry cmsx_menuFilterPerProfileEntries[] = { { "DTERM LPF2 ROLL", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lowpass2_hz_roll, 0, 500, 1 }, 0 }, { "DTERM LPF2 PITCH", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lowpass2_hz_pitch, 0, 500, 1 }, 0 }, { "DTERM LPF2 YAW", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lowpass2_hz_yaw, 0, 500, 1 }, 0 }, +#ifdef USE_GYRO_DATA_ANALYSE { "DTERM DYN ENABLE", OME_TAB, NULL, &(OSD_TAB_t) { (uint8_t *) &cmsx_dterm_dyn_notch_enable, 1, cms_offOnLabels }, 0 }, { "DTERM DYN NOT Q", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_dyn_notch_q, 0, 2000, 1 }, 0 }, +#endif { "DTERM ABG ALPHA", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_abg_alpha, 0, 1000, 1 }, 0 }, { "DTERM ABG BOOST", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_abg_boost, 0, 2000, 1 }, 0 }, { "DTERM ABG HL", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_dterm_abg_half_life, 0, 250, 1 }, 0 }, diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 19b51d18f7..fe0585a8d0 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -197,8 +197,10 @@ void resetPidProfile(pidProfile_t *pidProfile) { .dterm_ABG_half_life = 50, .emuGravityGain = 50, .angle_filter = 100, +#ifdef USE_GYRO_DATA_ANALYSE .dtermDynNotch = false, .dterm_dyn_notch_q = 400, +#endif ); } @@ -811,7 +813,7 @@ void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *an float dDelta = ((feathered_pids * pureMeasurement) + ((1 - feathered_pids) * pureError)) * pidFrequency; //calculating the dterm determine how much is calculated using measurement vs error //filter the dterm #ifdef USE_GYRO_DATA_ANALYSE - if (isDynamicFilterActive() && pidProfile->dtermDynNotch) { + if (isDynamicFilterActive() && pidProfile->dtermDynNotch && axis <= gyroConfig()->dyn_notch_axis+1) { for (int p = 0; p < gyroConfig()->dyn_notch_count; p++) { if (getCenterFreq(axis, p) != previousNotchCenterFreq[axis][p]) { previousNotchCenterFreq[axis][p] = getCenterFreq(axis, p); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index ea9f16d811..bfe63e31f0 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -155,8 +155,10 @@ typedef struct pidProfile_s { uint16_t dterm_ABG_alpha; uint16_t dterm_ABG_boost; uint8_t dterm_ABG_half_life; +#ifdef USE_GYRO_DATA_ANALYSE uint8_t dtermDynNotch; uint16_t dterm_dyn_notch_q; +#endif } pidProfile_t; #ifndef USE_OSD_SLAVE diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index b3aebb427d..9b3dd142da 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1204,10 +1204,17 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { sbufWriteU16(dst, currentPidProfile->dFilter[YAW].dLpf2); //MSP 1.51 removes SmartDTermSmoothing and WitchCraft //MSP 1.51 adds and refactors dynamic_filter +#ifdef USE_GYRO_DATA_ANALYSE sbufWriteU8(dst, gyroConfig()->dyn_notch_count); //dynamic_gyro_notch_count sbufWriteU16(dst, gyroConfig()->dyn_notch_q); sbufWriteU16(dst, gyroConfig()->dyn_notch_min_hz); sbufWriteU16(dst, gyroConfig()->dyn_notch_max_hz); //dynamic_gyro_notch_max_hz +#else + sbufWriteU8(dst, 0); + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); +#endif //end MSP 1.51 add/refactor dynamic filter //MSP 1.51 sbufWriteU16(dst, gyroConfig()->gyro_ABG_alpha); @@ -1219,8 +1226,13 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { sbufWriteU8(dst, currentPidProfile->dterm_ABG_half_life); //end MSP 1.51 //MSP 1.51 dynamic dTerm notch +#ifdef USE_GYRO_DATA_ANALYSE sbufWriteU8(dst, currentPidProfile->dtermDynNotch); //dterm_dyn_notch_enable sbufWriteU16(dst, currentPidProfile->dterm_dyn_notch_q); //dterm_dyn_notch_q +#else + sbufWriteU8(dst, 0); + sbufWriteU16(dst, 0); +#endif //end MSP 1.51 dynamic dTerm notch break; /*#ifndef USE_GYRO_IMUF9001 @@ -1821,10 +1833,17 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { currentPidProfile->dFilter[YAW].dLpf2 = sbufReadU16(src); //MSP 1.51 removes SmartDTermSmoothing and WitchCraft //MSP 1.51 adds and refactors dynamic_filter +#ifdef USE_GYRO_DATA_ANALYSE gyroConfigMutable()->dyn_notch_count = sbufReadU8(src); //dynamic_gyro_notch_count gyroConfigMutable()->dyn_notch_q = sbufReadU16(src); gyroConfigMutable()->dyn_notch_min_hz = sbufReadU16(src); gyroConfigMutable()->dyn_notch_max_hz = sbufReadU16(src); //dynamic_gyro_notch_max_hz +#else + sbufReadU8(src); + sbufReadU16(src); + sbufReadU16(src); + sbufReadU16(src); +#endif //end 1.51 add/refactor dynamic_filter //MSP 1.51 gyroConfigMutable()->gyro_ABG_alpha = sbufReadU16(src); @@ -1836,8 +1855,13 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { currentPidProfile->dterm_ABG_half_life = sbufReadU8(src); //end MSP 1.51 //MSP 1.51 dynamic dTerm notch +#ifdef USE_GYRO_DATA_ANALYSE currentPidProfile->dtermDynNotch = sbufReadU8(src); //dterm_dyn_notch_enable currentPidProfile->dterm_dyn_notch_q = sbufReadU16(src); //dterm_dyn_notch_q +#else + sbufReadU8(src); + sbufReadU16(src); +#endif //end MSP 1.51 dynamic dTerm notch } // reinitialize the gyro filters with the new values diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 9634ec73c8..19f857c663 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -293,6 +293,7 @@ static const char * const lookupTableRcInterpolation[] = { static const char * const lookupTableRcInterpolationChannels[] = { "RP", "RPY", "RPYT", "T", "RPT", }; + static const char * const lookupTableFilterType[] = { "PT1", "BIQUAD", "PT2", "PT3", "PT4", }; @@ -393,6 +394,12 @@ static const char *const lookupTableMixerImplType[] = { "LEGACY", "SMOOTH", "2PASS" }; +#ifdef USE_GYRO_DATA_ANALYSE +static const char *const lookupTableDynNotchAxisType[] = { + "RP", "RPY" +}; +#endif + #define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) } const lookupTableEntry_t lookupTables[] = { @@ -482,6 +489,9 @@ const lookupTableEntry_t lookupTables[] = { LOOKUP_TABLE_ENTRY(lookupTableOsdLogoOnArming), #endif LOOKUP_TABLE_ENTRY(lookupTableMixerImplType), +#ifdef USE_GYRO_DATA_ANALYSE + LOOKUP_TABLE_ENTRY(lookupTableDynNotchAxisType), +#endif }; #undef LOOKUP_TABLE_ENTRY @@ -553,6 +563,7 @@ const clivalue_t valueTable[] = { { "gyro_to_use", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_to_use) }, #endif #if defined(USE_GYRO_DATA_ANALYSE) + { "dynamic_gyro_notch_axis", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DYN_NOTCH_AXIS_TYPE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_axis) }, { "dynamic_gyro_notch_q", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_q) }, { "dynamic_gyro_notch_count", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 5 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_count) }, { "dynamic_gyro_notch_min_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 30, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, dyn_notch_min_hz) }, @@ -863,9 +874,10 @@ const clivalue_t valueTable[] = { { "runaway_takeoff_deactivate_throttle_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_PID_CONFIG, offsetof(pidConfig_t, runaway_takeoff_deactivate_throttle) }, // minimum throttle percentage during deactivation phase #endif // PG_PID_PROFILE +#ifdef USE_GYRO_DATA_ANALYSE { "dterm_dyn_notch_enable", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, dtermDynNotch) }, { "dterm_dyn_notch_q", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_dyn_notch_q) }, - +#endif { "dterm_abg_alpha", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_ABG_alpha) }, { "dterm_abg_boost", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 2000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_ABG_boost) }, { "dterm_abg_half_life", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 250 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_ABG_half_life) }, diff --git a/src/main/interface/settings.h b/src/main/interface/settings.h index f351a2aa12..ab5ea4482e 100644 --- a/src/main/interface/settings.h +++ b/src/main/interface/settings.h @@ -112,6 +112,9 @@ typedef enum { TABLE_OSD_LOGO_ON_ARMING, #endif TABLE_MIXER_IMPL_TYPE, +#ifdef USE_GYRO_DATA_ANALYSE + TABLE_DYN_NOTCH_AXIS_TYPE, +#endif LOOKUP_TABLE_COUNT } lookupTableIndex_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index b77528e9fd..b957ac7ef3 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -250,10 +250,13 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .checkOverflow = GYRO_OVERFLOW_CHECK_ALL_AXES, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, +#ifdef USE_GYRO_DATA_ANALYSE + .dyn_notch_axis = RPY, .dyn_notch_q = 400, .dyn_notch_count = 3, // default of 3 is similar to the matrix filter. .dyn_notch_min_hz = 150, .dyn_notch_max_hz = 600, +#endif .imuf_mode = GTBCM_GYRO_ACC_FILTER_F, .imuf_rate = IMUF_RATE_16K, .imuf_roll_q = 6000, @@ -305,10 +308,13 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_offset_yaw = 0, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, +#ifdef USE_GYRO_DATA_ANALYSE + .dyn_notch_axis = RPY, .dyn_notch_q = 350, .dyn_notch_count = 3, // default of 3 is similar to the matrix filter. .dyn_notch_min_hz = 150, .dyn_notch_max_hz = 600, +#endif .gyro_ABG_alpha = 0, .gyro_ABG_boost = 275, .gyro_ABG_half_life = 50, @@ -843,7 +849,7 @@ static void gyroInitFilterDynamicNotch(gyroSensor_t *gyroSensor) { gyroSensor->notchFilterDynApplyFn = nullFilterApply; if (isDynamicFilterActive()) { gyroSensor->notchFilterDynApplyFn = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2 - for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + for (int axis = 0; axis < gyroConfig()->dyn_notch_axis+1; axis++) { for (int axis2 = 0; axis2 < gyroConfig()->dyn_notch_count; axis2++) { biquadFilterInit(&gyroSensor->gyroAnalyseState.notchFilterDyn[axis][axis2], 400, gyro.targetLooptime, gyroConfig()->dyn_notch_q / 100.0f, FILTER_NOTCH); } diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 0f32c699e1..84bee04419 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -113,6 +113,13 @@ typedef struct smithPredictor_s { } smithPredictor_t; #endif // USE_SMITH_PREDICTOR +#ifdef USE_GYRO_DATA_ANALYSE +typedef enum { + RP = 0, + RPY = 1 +} dynamicGyroAxisType_e; +#endif + typedef struct gyroConfig_s { uint8_t gyro_align; // gyro alignment uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. @@ -146,10 +153,13 @@ typedef struct gyroConfig_s { int16_t yaw_spin_threshold; uint16_t gyroCalibrationDuration; // Gyro calibration duration in 1/100 second +#if defined(USE_GYRO_DATA_ANALYSE) + uint8_t dyn_notch_axis; uint16_t dyn_notch_q; uint8_t dyn_notch_count; uint16_t dyn_notch_min_hz; uint16_t dyn_notch_max_hz; +#endif #if defined(USE_GYRO_IMUF9001) uint16_t imuf_mode; uint16_t imuf_rate; From de71a3a275047d084d3ba7da584c0286ff906248 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 26 Oct 2023 08:23:46 -0500 Subject: [PATCH 23/37] add Gyro LPF2 type to OSD (#934) --- src/main/cms/cms_menu_imu.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index e479a1fa17..64be1292d8 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -493,6 +493,7 @@ static uint8_t gyroConfig_gyro_lowpass1_type; static uint16_t gyroConfig_gyro_lowpass_hz_roll; static uint16_t gyroConfig_gyro_lowpass_hz_pitch; static uint16_t gyroConfig_gyro_lowpass_hz_yaw; +static uint8_t gyroConfig_gyro_lowpass2_type; static uint16_t gyroConfig_gyro_lowpass2_hz_roll; static uint16_t gyroConfig_gyro_lowpass2_hz_pitch; static uint16_t gyroConfig_gyro_lowpass2_hz_yaw; @@ -524,6 +525,7 @@ static long cmsx_menuGyro_onEnter(void) { gyroConfig_gyro_lowpass_hz_roll = gyroConfig()->gyro_lowpass_hz[ROLL]; gyroConfig_gyro_lowpass_hz_pitch = gyroConfig()->gyro_lowpass_hz[PITCH]; gyroConfig_gyro_lowpass_hz_yaw = gyroConfig()->gyro_lowpass_hz[YAW]; + gyroConfig_gyro_lowpass2_type = gyroConfig()->gyro_lowpass2_type; gyroConfig_gyro_lowpass2_hz_roll = gyroConfig()->gyro_lowpass2_hz[ROLL]; gyroConfig_gyro_lowpass2_hz_pitch = gyroConfig()->gyro_lowpass2_hz[PITCH]; gyroConfig_gyro_lowpass2_hz_yaw = gyroConfig()->gyro_lowpass2_hz[YAW]; @@ -558,6 +560,7 @@ static long cmsx_menuGyro_onExit(const OSD_Entry *self) { gyroConfigMutable()->gyro_lowpass_hz[ROLL] = gyroConfig_gyro_lowpass_hz_roll; gyroConfigMutable()->gyro_lowpass_hz[PITCH] = gyroConfig_gyro_lowpass_hz_pitch; gyroConfigMutable()->gyro_lowpass_hz[YAW] = gyroConfig_gyro_lowpass_hz_yaw; + gyroConfigMutable()->gyro_lowpass2_type = gyroConfig_gyro_lowpass2_type; gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = gyroConfig_gyro_lowpass2_hz_roll; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = gyroConfig_gyro_lowpass2_hz_pitch; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = gyroConfig_gyro_lowpass2_hz_yaw; @@ -589,11 +592,12 @@ static long cmsx_menuGyro_onExit(const OSD_Entry *self) { static OSD_Entry cmsx_menuFilterGlobalEntries[] = { { "-- FILTER GLB --", OME_Label, NULL, NULL, 0 }, + { "GYRO LPF TYPE", OME_TAB, NULL, &(OSD_TAB_t) { (uint8_t *) &gyroConfig_gyro_lowpass1_type, 4, cms_FilterType }, 0 }, { "GYRO LPF ROLL", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass_hz_roll, 0, 16000, 1 }, 0 }, { "GYRO LPF PITCH", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass_hz_pitch, 0, 16000, 1 }, 0 }, { "GYRO LPF YAW", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass_hz_yaw, 0, 16000, 1 }, 0 }, - { "GYRO LPF TYPE", OME_TAB, NULL, &(OSD_TAB_t) { (uint8_t *) &gyroConfig_gyro_lowpass1_type, 4, cms_FilterType }, 0 }, #ifdef USE_GYRO_LPF2 + { "GYRO LPF2 TYPE", OME_TAB, NULL, &(OSD_TAB_t) { (uint8_t *) &gyroConfig_gyro_lowpass2_type, 4, cms_FilterType }, 0 }, { "GYRO LPF2 ROLL", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass2_hz_roll, 0, 16000, 1 }, 0 }, { "GYRO LPF2 PITCH", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass2_hz_pitch, 0, 16000, 1 }, 0 }, { "GYRO LPF2 YAW", OME_UINT16, NULL, &(OSD_UINT16_t) { &gyroConfig_gyro_lowpass2_hz_yaw, 0, 16000, 1 }, 0 }, From db57386cd614604c83db951e16d36d224641918a Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 26 Oct 2023 09:49:06 -0500 Subject: [PATCH 24/37] fix/add USE_GYRO_LPF2 gating (#935) * fix/add USE_GYRO_LPF2 gating --- src/main/blackbox/blackbox.c | 2 ++ src/main/cms/cms_menu_imu.c | 6 ++++++ src/main/interface/msp.c | 20 ++++++++++++++++++++ src/main/interface/settings.c | 2 ++ src/main/sensors/gyro.c | 10 ++++++++++ src/main/sensors/gyro.h | 4 ++++ src/main/sensors/gyro_filter_impl.h | 2 ++ src/main/target/NBDBBBLV2/config.c | 2 ++ src/main/target/NBDBBBLV3/config.c | 2 ++ src/main/target/NBDHMBF41S/config.c | 2 ++ src/main/target/NBDHMBF4PRO/config.c | 2 ++ src/test/unit/sensor_gyro_unittest.cc | 2 ++ 12 files changed, 56 insertions(+) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 672d39fc3a..436871abb4 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1229,10 +1229,12 @@ static bool blackboxWriteSysinfo(void) { BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz_roll", "%d", gyroConfig()->gyro_lowpass_hz[ROLL]); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz_pitch", "%d", gyroConfig()->gyro_lowpass_hz[PITCH]); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz_yaw", "%d", gyroConfig()->gyro_lowpass_hz[YAW]); +#ifdef USE_GYRO_LPF2 BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass2_type", "%d", gyroConfig()->gyro_lowpass2_type); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass2_hz_roll", "%d", gyroConfig()->gyro_lowpass2_hz[ROLL]); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass2_hz_pitch", "%d", gyroConfig()->gyro_lowpass2_hz[PITCH]); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass2_hz_yaw", "%d", gyroConfig()->gyro_lowpass2_hz[YAW]); +#endif BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_hz_2); BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1, diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index 64be1292d8..50c0bfc589 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -493,10 +493,12 @@ static uint8_t gyroConfig_gyro_lowpass1_type; static uint16_t gyroConfig_gyro_lowpass_hz_roll; static uint16_t gyroConfig_gyro_lowpass_hz_pitch; static uint16_t gyroConfig_gyro_lowpass_hz_yaw; +#ifdef USE_GYRO_LPF2 static uint8_t gyroConfig_gyro_lowpass2_type; static uint16_t gyroConfig_gyro_lowpass2_hz_roll; static uint16_t gyroConfig_gyro_lowpass2_hz_pitch; static uint16_t gyroConfig_gyro_lowpass2_hz_yaw; +#endif #ifdef USE_GYRO_DATA_ANALYSE static uint16_t gyroConfig_gyro_q; static uint8_t gyroConfig_gyro_notch_count; @@ -525,10 +527,12 @@ static long cmsx_menuGyro_onEnter(void) { gyroConfig_gyro_lowpass_hz_roll = gyroConfig()->gyro_lowpass_hz[ROLL]; gyroConfig_gyro_lowpass_hz_pitch = gyroConfig()->gyro_lowpass_hz[PITCH]; gyroConfig_gyro_lowpass_hz_yaw = gyroConfig()->gyro_lowpass_hz[YAW]; +#ifdef USE_GYRO_LPF2 gyroConfig_gyro_lowpass2_type = gyroConfig()->gyro_lowpass2_type; gyroConfig_gyro_lowpass2_hz_roll = gyroConfig()->gyro_lowpass2_hz[ROLL]; gyroConfig_gyro_lowpass2_hz_pitch = gyroConfig()->gyro_lowpass2_hz[PITCH]; gyroConfig_gyro_lowpass2_hz_yaw = gyroConfig()->gyro_lowpass2_hz[YAW]; +#endif #ifdef USE_GYRO_DATA_ANALYSE gyroConfig_gyro_q = gyroConfig()->dyn_notch_q; gyroConfig_gyro_notch_count = gyroConfig()->dyn_notch_count; @@ -560,10 +564,12 @@ static long cmsx_menuGyro_onExit(const OSD_Entry *self) { gyroConfigMutable()->gyro_lowpass_hz[ROLL] = gyroConfig_gyro_lowpass_hz_roll; gyroConfigMutable()->gyro_lowpass_hz[PITCH] = gyroConfig_gyro_lowpass_hz_pitch; gyroConfigMutable()->gyro_lowpass_hz[YAW] = gyroConfig_gyro_lowpass_hz_yaw; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_type = gyroConfig_gyro_lowpass2_type; gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = gyroConfig_gyro_lowpass2_hz_roll; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = gyroConfig_gyro_lowpass2_hz_pitch; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = gyroConfig_gyro_lowpass2_hz_yaw; +#endif #ifdef USE_GYRO_DATA_ANALYSE gyroConfigMutable()->dyn_notch_q = gyroConfig_gyro_q; gyroConfigMutable()->dyn_notch_count = gyroConfig_gyro_notch_count; diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index 9b3dd142da..a748c4aeb4 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1194,11 +1194,21 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { sbufWriteU16(dst, gyroConfig()->gyro_lowpass_hz[ROLL]); sbufWriteU16(dst, gyroConfig()->gyro_lowpass_hz[PITCH]); sbufWriteU16(dst, gyroConfig()->gyro_lowpass_hz[YAW]); +#ifdef USE_GYRO_LPF2 sbufWriteU16(dst, gyroConfig()->gyro_lowpass2_hz[ROLL]); sbufWriteU16(dst, gyroConfig()->gyro_lowpass2_hz[PITCH]); sbufWriteU16(dst, gyroConfig()->gyro_lowpass2_hz[YAW]); +#else + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); +#endif sbufWriteU8(dst, gyroConfig()->gyro_lowpass_type); +#ifdef USE_GYRO_LPF2 sbufWriteU8(dst, gyroConfig()->gyro_lowpass2_type); +#else + sbufWriteU8(dst, 0); +#endif sbufWriteU16(dst, currentPidProfile->dFilter[ROLL].dLpf2); sbufWriteU16(dst, currentPidProfile->dFilter[PITCH].dLpf2); sbufWriteU16(dst, currentPidProfile->dFilter[YAW].dLpf2); @@ -1823,11 +1833,21 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { gyroConfigMutable()->gyro_lowpass_hz[ROLL] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass_hz[PITCH] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass_hz[YAW] = sbufReadU16(src); +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass2_hz[YAW] = sbufReadU16(src); +#else + sbufReadU16(src); + sbufReadU16(src); + sbufReadU16(src); +#endif gyroConfigMutable()->gyro_lowpass_type = sbufReadU8(src); +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_type = sbufReadU8(src); +#else + sbufReadU8(src); +#endif currentPidProfile->dFilter[ROLL].dLpf2 = sbufReadU16(src); currentPidProfile->dFilter[PITCH].dLpf2 = sbufReadU16(src); currentPidProfile->dFilter[YAW].dLpf2 = sbufReadU16(src); diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 19f857c663..cb2690eb58 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -513,10 +513,12 @@ const clivalue_t valueTable[] = { { "gyro_lowpass_hz_pitch", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass_hz[PITCH]) }, { "gyro_lowpass_hz_yaw", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass_hz[YAW]) }, +#ifdef USE_GYRO_LPF2 { "gyro_lowpass2_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FILTER_TYPE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass2_type) }, { "gyro_lowpass2_hz_roll", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass2_hz[ROLL]) }, { "gyro_lowpass2_hz_pitch", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass2_hz[PITCH]) }, { "gyro_lowpass2_hz_yaw", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lowpass2_hz[YAW]) }, +#endif { "gyro_abg_alpha", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_ABG_alpha) }, { "gyro_abg_boost", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_ABG_boost) }, diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index b957ac7ef3..cb2c2c6b03 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -158,8 +158,10 @@ typedef struct gyroSensor_s { gyroLowpassFilter_t lowpassFilter[XYZ_AXIS_COUNT]; // lowpass2 gyro soft filter +#ifdef USE_GYRO_LPF2 filterApplyFnPtr lowpass2FilterApplyFn; gyroLowpassFilter_t lowpass2Filter[XYZ_AXIS_COUNT]; +#endif // ABG filter filterApplyFnPtr gyroABGFilterApplyFn; @@ -236,10 +238,12 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lowpass_hz[ROLL] = 0, .gyro_lowpass_hz[PITCH] = 0, .gyro_lowpass_hz[YAW] = 0, +#ifdef USE_GYRO_LPF2 .gyro_lowpass2_type = FILTER_PT1, .gyro_lowpass2_hz[ROLL] = 0, .gyro_lowpass2_hz[PITCH] = 0, .gyro_lowpass2_hz[YAW] = 0, +#endif .gyro_high_fsr = false, .gyro_use_32khz = true, .gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT, @@ -289,10 +293,12 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lowpass_hz[ROLL] = 115, .gyro_lowpass_hz[PITCH] = 115, .gyro_lowpass_hz[YAW] = 105, +#ifdef USE_GYRO_LPF2 .gyro_lowpass2_type = FILTER_PT1, .gyro_lowpass2_hz[ROLL] = 0, .gyro_lowpass2_hz[PITCH] = 0, .gyro_lowpass2_hz[YAW] = 0, +#endif .gyro_high_fsr = false, .gyro_use_32khz = false, .gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT, @@ -749,6 +755,7 @@ void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int type) { lpfHz[PITCH] = gyroConfig()->gyro_lowpass_hz[PITCH]; lpfHz[YAW] = gyroConfig()->gyro_lowpass_hz[YAW]; break; +#ifdef USE_GYRO_LPF2 case FILTER_LOWPASS2: lowpassFilterApplyFn = &gyroSensor->lowpass2FilterApplyFn; lowpassFilter = gyroSensor->lowpass2Filter; @@ -756,6 +763,7 @@ void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int type) { lpfHz[PITCH] = gyroConfig()->gyro_lowpass2_hz[PITCH]; lpfHz[YAW] = gyroConfig()->gyro_lowpass2_hz[YAW]; break; +#endif default: return; } @@ -894,11 +902,13 @@ static void gyroInitSensorFilters(gyroSensor_t *gyroSensor) { FILTER_LOWPASS, gyroConfig()->gyro_lowpass_type ); +#ifdef USE_GYRO_LPF2 gyroInitLowpassFilterLpf( gyroSensor, FILTER_LOWPASS2, gyroConfig()->gyro_lowpass2_type ); +#endif gyroInitFilterNotch1(gyroSensor, gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1); gyroInitFilterNotch2(gyroSensor, gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2); #ifdef USE_GYRO_DATA_ANALYSE diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 84bee04419..403954835e 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -132,7 +132,9 @@ typedef struct gyroConfig_s { uint8_t gyro_to_use; uint16_t gyro_lowpass_hz[XYZ_AXIS_COUNT]; +#ifdef USE_GYRO_LPF2 uint16_t gyro_lowpass2_hz[XYZ_AXIS_COUNT]; +#endif uint16_t gyro_ABG_alpha; uint16_t gyro_ABG_boost; @@ -147,7 +149,9 @@ typedef struct gyroConfig_s { // Lowpass primary/secondary uint8_t gyro_lowpass_type; +#ifdef USE_GYRO_LPF2 uint8_t gyro_lowpass2_type; +#endif uint8_t yaw_spin_recovery; int16_t yaw_spin_threshold; diff --git a/src/main/sensors/gyro_filter_impl.h b/src/main/sensors/gyro_filter_impl.h index 2008434496..4bf1060e19 100644 --- a/src/main/sensors/gyro_filter_impl.h +++ b/src/main/sensors/gyro_filter_impl.h @@ -36,7 +36,9 @@ static FAST_CODE void GYRO_FILTER_FUNCTION_NAME(gyroSensor_t *gyroSensor) { #endif // apply static notch filters and software lowpass filters +#ifdef USE_GYRO_LPF2 gyroADCf = gyroSensor->lowpass2FilterApplyFn((filter_t *)&gyroSensor->lowpass2Filter[axis], gyroADCf); +#endif gyroADCf = gyroSensor->lowpassFilterApplyFn((filter_t *)&gyroSensor->lowpassFilter[axis], gyroADCf); gyroADCf = gyroSensor->notchFilter1ApplyFn((filter_t *)&gyroSensor->notchFilter1[axis], gyroADCf); gyroADCf = gyroSensor->notchFilter2ApplyFn((filter_t *)&gyroSensor->notchFilter2[axis], gyroADCf); diff --git a/src/main/target/NBDBBBLV2/config.c b/src/main/target/NBDBBBLV2/config.c index 2c735aec79..407f0f6f97 100644 --- a/src/main/target/NBDBBBLV2/config.c +++ b/src/main/target/NBDBBBLV2/config.c @@ -168,9 +168,11 @@ void targetConfiguration(void) gyroConfigMutable()->gyro_lowpass_hz[ROLL] = 200; gyroConfigMutable()->gyro_lowpass_hz[PITCH] = 200; gyroConfigMutable()->gyro_lowpass_hz[YAW] = 200; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = 250; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = 250; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = 250; +#endif gyroConfigMutable()->yaw_spin_threshold = 1950; rxConfigMutable()->mincheck = 1075; rxConfigMutable()->maxcheck = 1900; diff --git a/src/main/target/NBDBBBLV3/config.c b/src/main/target/NBDBBBLV3/config.c index 27f7b894ad..0774446586 100644 --- a/src/main/target/NBDBBBLV3/config.c +++ b/src/main/target/NBDBBBLV3/config.c @@ -168,9 +168,11 @@ void targetConfiguration(void) gyroConfigMutable()->gyro_lowpass_hz[ROLL] = 200; gyroConfigMutable()->gyro_lowpass_hz[PITCH] = 200; gyroConfigMutable()->gyro_lowpass_hz[YAW] = 200; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = 250; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = 250; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = 250; +#endif gyroConfigMutable()->yaw_spin_threshold = 1950; rxConfigMutable()->mincheck = 1075; rxConfigMutable()->maxcheck = 1900; diff --git a/src/main/target/NBDHMBF41S/config.c b/src/main/target/NBDHMBF41S/config.c index 493da570e9..92fe2d8b70 100644 --- a/src/main/target/NBDHMBF41S/config.c +++ b/src/main/target/NBDHMBF41S/config.c @@ -114,7 +114,9 @@ void targetConfiguration(void) gyroConfigMutable()->gyro_lowpass_type = FILTER_PT1; gyroConfigMutable()->gyro_lowpass_hz = 200; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz = 200; +#endif gyroConfigMutable()->yaw_spin_threshold = 1950; gyroConfigMutable()->dyn_lpf_gyro_min_hz = 160; gyroConfigMutable()->dyn_lpf_gyro_max_hz = 400; diff --git a/src/main/target/NBDHMBF4PRO/config.c b/src/main/target/NBDHMBF4PRO/config.c index 42862bed35..fd309465bc 100644 --- a/src/main/target/NBDHMBF4PRO/config.c +++ b/src/main/target/NBDHMBF4PRO/config.c @@ -149,9 +149,11 @@ void targetConfiguration(void) { gyroConfigMutable()->gyro_lowpass_hz[ROLL] = 200; gyroConfigMutable()->gyro_lowpass_hz[PITCH] = 200; gyroConfigMutable()->gyro_lowpass_hz[YAW] = 200; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = 250; gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = 250; gyroConfigMutable()->gyro_lowpass2_hz[YAW] = 250; +#endif gyroConfigMutable()->yaw_spin_threshold = 1950; // gyroConfigMutable()->dyn_lpf_gyro_min_hz = 200; // gyroConfigMutable()->dyn_lpf_gyro_max_hz = 500; diff --git a/src/test/unit/sensor_gyro_unittest.cc b/src/test/unit/sensor_gyro_unittest.cc index fc2dbc20e4..0ee0877b84 100644 --- a/src/test/unit/sensor_gyro_unittest.cc +++ b/src/test/unit/sensor_gyro_unittest.cc @@ -116,7 +116,9 @@ TEST(SensorGyro, Update) pgResetAll(); // turn off filters gyroConfigMutable()->gyro_lowpass_hz[ROLL] = 0; +#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = 0; +#endif gyroConfigMutable()->gyro_soft_notch_hz_1 = 0; gyroConfigMutable()->gyro_soft_notch_hz_2 = 0; gyroInit(); From b2117eb9c6606d804c7361a3b6a08b1c9f6b5b95 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Fri, 27 Oct 2023 10:54:51 -0500 Subject: [PATCH 25/37] revert some USE_GYRO_DATA_ANALYSE and USE_GYRO_LPF2 gating (#936) revert some USE_GYRO_DATA_ANALYSE and USE_GYRO_LPF2 gating because C compiler sucks --- src/main/flight/pid.c | 6 ++++-- src/main/flight/pid.h | 2 -- src/main/interface/msp.c | 22 ---------------------- src/main/interface/settings.c | 4 ---- src/main/interface/settings.h | 2 -- src/main/sensors/gyro.c | 8 -------- src/main/sensors/gyro.h | 8 -------- 7 files changed, 4 insertions(+), 48 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index fe0585a8d0..231c6fa489 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -197,10 +197,8 @@ void resetPidProfile(pidProfile_t *pidProfile) { .dterm_ABG_half_life = 50, .emuGravityGain = 50, .angle_filter = 100, -#ifdef USE_GYRO_DATA_ANALYSE .dtermDynNotch = false, .dterm_dyn_notch_q = 400, -#endif ); } @@ -237,7 +235,9 @@ static FAST_RAM filterApplyFnPtr angleSetpointFilterApplyFn = nullFilterApply; static FAST_RAM_ZERO_INIT pt1Filter_t angleSetpointFilter[2]; static FAST_RAM filterApplyFnPtr dtermABGapplyFn = nullFilterApply; static FAST_RAM_ZERO_INIT alphaBetaGammaFilter_t dtermABG[XYZ_AXIS_COUNT]; +#ifdef USE_GYRO_DATA_ANALYSE static FAST_RAM_ZERO_INIT biquadFilter_t dtermNotch[XYZ_AXIS_COUNT][5]; +#endif #if defined(USE_ITERM_RELAX) static FAST_RAM_ZERO_INIT pt1Filter_t windupLpf[XYZ_AXIS_COUNT]; @@ -673,7 +673,9 @@ static FAST_RAM_ZERO_INIT float stickMovement[XYZ_AXIS_COUNT]; static FAST_RAM_ZERO_INIT float lastRcDeflectionAbs[XYZ_AXIS_COUNT]; static FAST_RAM_ZERO_INIT float previousError[XYZ_AXIS_COUNT]; static FAST_RAM_ZERO_INIT float previousMeasurement[XYZ_AXIS_COUNT]; +#ifdef USE_GYRO_DATA_ANALYSE static FAST_RAM_ZERO_INIT float previousNotchCenterFreq[XYZ_AXIS_COUNT][5]; +#endif static FAST_RAM_ZERO_INIT timeUs_t crashDetectedAtUs; void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *angleTrim, timeUs_t currentTimeUs) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index bfe63e31f0..ea9f16d811 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -155,10 +155,8 @@ typedef struct pidProfile_s { uint16_t dterm_ABG_alpha; uint16_t dterm_ABG_boost; uint8_t dterm_ABG_half_life; -#ifdef USE_GYRO_DATA_ANALYSE uint8_t dtermDynNotch; uint16_t dterm_dyn_notch_q; -#endif } pidProfile_t; #ifndef USE_OSD_SLAVE diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index a748c4aeb4..684b85e213 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1833,37 +1833,20 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { gyroConfigMutable()->gyro_lowpass_hz[ROLL] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass_hz[PITCH] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass_hz[YAW] = sbufReadU16(src); -#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = sbufReadU16(src); gyroConfigMutable()->gyro_lowpass2_hz[YAW] = sbufReadU16(src); -#else - sbufReadU16(src); - sbufReadU16(src); - sbufReadU16(src); -#endif gyroConfigMutable()->gyro_lowpass_type = sbufReadU8(src); -#ifdef USE_GYRO_LPF2 gyroConfigMutable()->gyro_lowpass2_type = sbufReadU8(src); -#else - sbufReadU8(src); -#endif currentPidProfile->dFilter[ROLL].dLpf2 = sbufReadU16(src); currentPidProfile->dFilter[PITCH].dLpf2 = sbufReadU16(src); currentPidProfile->dFilter[YAW].dLpf2 = sbufReadU16(src); //MSP 1.51 removes SmartDTermSmoothing and WitchCraft //MSP 1.51 adds and refactors dynamic_filter -#ifdef USE_GYRO_DATA_ANALYSE gyroConfigMutable()->dyn_notch_count = sbufReadU8(src); //dynamic_gyro_notch_count gyroConfigMutable()->dyn_notch_q = sbufReadU16(src); gyroConfigMutable()->dyn_notch_min_hz = sbufReadU16(src); gyroConfigMutable()->dyn_notch_max_hz = sbufReadU16(src); //dynamic_gyro_notch_max_hz -#else - sbufReadU8(src); - sbufReadU16(src); - sbufReadU16(src); - sbufReadU16(src); -#endif //end 1.51 add/refactor dynamic_filter //MSP 1.51 gyroConfigMutable()->gyro_ABG_alpha = sbufReadU16(src); @@ -1875,13 +1858,8 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { currentPidProfile->dterm_ABG_half_life = sbufReadU8(src); //end MSP 1.51 //MSP 1.51 dynamic dTerm notch -#ifdef USE_GYRO_DATA_ANALYSE currentPidProfile->dtermDynNotch = sbufReadU8(src); //dterm_dyn_notch_enable currentPidProfile->dterm_dyn_notch_q = sbufReadU16(src); //dterm_dyn_notch_q -#else - sbufReadU8(src); - sbufReadU16(src); -#endif //end MSP 1.51 dynamic dTerm notch } // reinitialize the gyro filters with the new values diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index cb2690eb58..9af64f98e5 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -394,11 +394,9 @@ static const char *const lookupTableMixerImplType[] = { "LEGACY", "SMOOTH", "2PASS" }; -#ifdef USE_GYRO_DATA_ANALYSE static const char *const lookupTableDynNotchAxisType[] = { "RP", "RPY" }; -#endif #define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) } @@ -489,9 +487,7 @@ const lookupTableEntry_t lookupTables[] = { LOOKUP_TABLE_ENTRY(lookupTableOsdLogoOnArming), #endif LOOKUP_TABLE_ENTRY(lookupTableMixerImplType), -#ifdef USE_GYRO_DATA_ANALYSE LOOKUP_TABLE_ENTRY(lookupTableDynNotchAxisType), -#endif }; #undef LOOKUP_TABLE_ENTRY diff --git a/src/main/interface/settings.h b/src/main/interface/settings.h index ab5ea4482e..e8a8269834 100644 --- a/src/main/interface/settings.h +++ b/src/main/interface/settings.h @@ -112,9 +112,7 @@ typedef enum { TABLE_OSD_LOGO_ON_ARMING, #endif TABLE_MIXER_IMPL_TYPE, -#ifdef USE_GYRO_DATA_ANALYSE TABLE_DYN_NOTCH_AXIS_TYPE, -#endif LOOKUP_TABLE_COUNT } lookupTableIndex_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index cb2c2c6b03..eefea7e341 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -238,12 +238,10 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lowpass_hz[ROLL] = 0, .gyro_lowpass_hz[PITCH] = 0, .gyro_lowpass_hz[YAW] = 0, -#ifdef USE_GYRO_LPF2 .gyro_lowpass2_type = FILTER_PT1, .gyro_lowpass2_hz[ROLL] = 0, .gyro_lowpass2_hz[PITCH] = 0, .gyro_lowpass2_hz[YAW] = 0, -#endif .gyro_high_fsr = false, .gyro_use_32khz = true, .gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT, @@ -254,13 +252,11 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .checkOverflow = GYRO_OVERFLOW_CHECK_ALL_AXES, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, -#ifdef USE_GYRO_DATA_ANALYSE .dyn_notch_axis = RPY, .dyn_notch_q = 400, .dyn_notch_count = 3, // default of 3 is similar to the matrix filter. .dyn_notch_min_hz = 150, .dyn_notch_max_hz = 600, -#endif .imuf_mode = GTBCM_GYRO_ACC_FILTER_F, .imuf_rate = IMUF_RATE_16K, .imuf_roll_q = 6000, @@ -293,12 +289,10 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lowpass_hz[ROLL] = 115, .gyro_lowpass_hz[PITCH] = 115, .gyro_lowpass_hz[YAW] = 105, -#ifdef USE_GYRO_LPF2 .gyro_lowpass2_type = FILTER_PT1, .gyro_lowpass2_hz[ROLL] = 0, .gyro_lowpass2_hz[PITCH] = 0, .gyro_lowpass2_hz[YAW] = 0, -#endif .gyro_high_fsr = false, .gyro_use_32khz = false, .gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT, @@ -314,13 +308,11 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_offset_yaw = 0, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, -#ifdef USE_GYRO_DATA_ANALYSE .dyn_notch_axis = RPY, .dyn_notch_q = 350, .dyn_notch_count = 3, // default of 3 is similar to the matrix filter. .dyn_notch_min_hz = 150, .dyn_notch_max_hz = 600, -#endif .gyro_ABG_alpha = 0, .gyro_ABG_boost = 275, .gyro_ABG_half_life = 50, diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 403954835e..b81475a75c 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -113,12 +113,10 @@ typedef struct smithPredictor_s { } smithPredictor_t; #endif // USE_SMITH_PREDICTOR -#ifdef USE_GYRO_DATA_ANALYSE typedef enum { RP = 0, RPY = 1 } dynamicGyroAxisType_e; -#endif typedef struct gyroConfig_s { uint8_t gyro_align; // gyro alignment @@ -132,9 +130,7 @@ typedef struct gyroConfig_s { uint8_t gyro_to_use; uint16_t gyro_lowpass_hz[XYZ_AXIS_COUNT]; -#ifdef USE_GYRO_LPF2 uint16_t gyro_lowpass2_hz[XYZ_AXIS_COUNT]; -#endif uint16_t gyro_ABG_alpha; uint16_t gyro_ABG_boost; @@ -149,21 +145,17 @@ typedef struct gyroConfig_s { // Lowpass primary/secondary uint8_t gyro_lowpass_type; -#ifdef USE_GYRO_LPF2 uint8_t gyro_lowpass2_type; -#endif uint8_t yaw_spin_recovery; int16_t yaw_spin_threshold; uint16_t gyroCalibrationDuration; // Gyro calibration duration in 1/100 second -#if defined(USE_GYRO_DATA_ANALYSE) uint8_t dyn_notch_axis; uint16_t dyn_notch_q; uint8_t dyn_notch_count; uint16_t dyn_notch_min_hz; uint16_t dyn_notch_max_hz; -#endif #if defined(USE_GYRO_IMUF9001) uint16_t imuf_mode; uint16_t imuf_rate; From 3fd882df176b98fd6c8df51153532dd583ba67dd Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Tue, 31 Oct 2023 15:21:47 -0500 Subject: [PATCH 26/37] ICM426XX - Disable AFSR (#933) * ICM426XX - Disable AFSR Betaflight: Disable ICM426XX AFSR feature to prevent stalls Ardupilot: AP_InertialSensor: fix for ICM42688 stuck gyro issue these undocumented bits in register 0x4d control the "adaptive full scale range" mode of the ICM42688. The feature is enabled by default but has a bug where it gives "stuck" gyro values for short periods (between 1ms and 2ms):, leading to a significant gyro bias at longer time scales, enough to in some cases cause a vehicle to crash if it is unable to switch to an alternative IMU Co-authored-by: Andrew Tridgell Co-authored-by: Steve Evans Thanks to all participants here: https://github.com/betaflight/betaflight/issues/12970 --- src/main/drivers/accgyro/accgyro_spi_icm426xx.c | 14 +++++++++++++- src/main/drivers/bus_spi.c | 3 ++- 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 24003f9017..0b284fcee7 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -48,6 +48,11 @@ #define ICM426XX_BANK_SELECT3 0x03 #define ICM426XX_BANK_SELECT4 0x04 +// Fix for stalls in gyro output. See https://github.com/ArduPilot/ardupilot/pull/25332 ; https://github.com/betaflight/betaflight/pull/13132 +#define ICM426XX_INTF_CONFIG1 0x4D +#define ICM426XX_INTF_CONFIG1_AFSR_MASK 0xC0 +#define ICM426XX_INTF_CONFIG1_AFSR_DISABLE 0x40 + #define ICM426XX_RA_PWR_MGMT0 0x4E // User Bank 0 #define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0) #define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2) @@ -284,13 +289,20 @@ void icm426xxGyroInit(gyroDev_t *gyro) spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED); - uint8_t intConfig1Value = spiReadRegMsk(&gyro->bus, ICM426XX_RA_INT_CONFIG1); + uint8_t intConfig1Value = spiBusReadRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1); // Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation" intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT); intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED); spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1, intConfig1Value); + // Disable AFSR to prevent stalls in gyro output + // ICM426XX_INTF_CONFIG1 location in user bank 0 + uint8_t intfConfig1Value = spiBusReadRegister(&gyro->bus, ICM426XX_INTF_CONFIG1); + intfConfig1Value &= ~ICM426XX_INTF_CONFIG1_AFSR_MASK; + intfConfig1Value |= ICM426XX_INTF_CONFIG1_AFSR_DISABLE; + spiBusWriteRegister(&gyro->bus, ICM426XX_INTF_CONFIG1, intfConfig1Value); + // Turn on gyro and acc on again so ODR and FSR can be configured turnGyroAccOn(gyro); diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index d42f0e6156..6bddbb9c5b 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -272,7 +272,8 @@ uint16_t spiCalculateDivider(uint32_t freq) return divisor; } -// Wait for bus to become free, then read a byte of data where the register is ORed with 0x80 +// Wait for bus to become free, then read a byte of data where the register is bitwise OR'ed with 0x80 +// EmuFlight codebase is old. Bitwise or 0x80 is redundant here as spiBusReadRegister already contains such. uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg) { return spiBusReadRegister(bus, reg | 0x80); From b1cf5d03f94284b1c2bc0ab46380f84a4e0878d6 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 1 Nov 2023 08:00:51 -0500 Subject: [PATCH 27/37] BMI270 Support - FIFO config file 328 bytes (#930) * BMI270 - WIP - failing - incl IFRC_IFLIGHT_F745_AIO_V2 for testing (nerdCopter) (2023-06-20) * bmi270 - add IFLIGHT_F745_AIO_V2 (nerdCopter from BeauBrewski) * bmi270 - fix my obvious mistakes (nerdCopter) * bmi270 - align ifrcf745aiov2 target (nerdCopter) * BMI270 should compile on IFLIGHT_F745_AIO_V2 target (Peck07) * add BMI270 support to BETAFPVF411 target (Peck07) * Delete accgyro_spi_bmi270.c.newww (Peck07) * change to OSD4 by default (Peck07)(discussed with nerdCopter) * put back a working getBmiOsrMode function (Peck07)(discussed with nerdCopter) * LPF_EXPERIMENTAL should give back OSR2 (Peck07) * unneeded files cleanup and file move; target path change (nerdCopter) * reorganize gyroRateKHz with switch/case; add bmi270 3.2 KHz (nerdCopter) * bmi270 - more file cleanup (nerdCopter) * bmi270 - switch/case - samplingTime (nerdCopter) * bmi270 targets - really not sure about this CS_PIN stuff (nerdCopter) * BMI270 - FOXEERF745_AIO (V2) (nerdCopter from BeauBrewski) * BMI270 - NBD_INFINITYAIOV2PRO (nerdCopter) * added SkystarsF7 target updates (BeauBrewski) * fix FLYWOOF411_5IN1_AIO align (nerdCopter) * BMI270 - gyro/pid denom default 1 (nerdCopter) * BMI270 - GYRO_HARDWARE_LPF_EXPERIMENTAL 3 (nerdCopter) * BMI270 - deduplicate spiCalculateDivider in bus_spi.h (nerdCopter) * BMI270 - remove OWNER_GYRO_EXTI from resource.h to fix breakage (nerdCopter) * BMI270 - gyro_hardware_lpf options (USE_GYRO_DLPF_EXPERIMENTAL) (nerdCopter) * BMI270 - replace OWNER_GYRO_EXTI with OWNER_MPU_EXTI (nerdCopter) * BMI270 - fix NBD_INFINITYAIOV2PRO dual-gyro defines (nerdCopter) * fix IFLIGHT_F745_AIO_V2 .mk (nerdCopter) * BMI270 - add bmi gyros to accgyro_mpu.h ifdef (nerdCopter) * BMI270 - fix detect - fixes requirement for mpu6000 defines (nerdCopter) * BMI270 - ensure over (nerdCopter) * BMI270 - move bmi270_maximum_fifo_config_file constant (nerdCopter) * BMI270 - remove extraneous fifo.c file inclusions (nerdCopter) * BMI270 - comment spiCalculateDivider (nerdCopter) * BMI270 - sync targets (nerdCopter) * BMI270 - remove targets and targets modification from this PR (nerdCopter) * BMI270 - emptyline cleanup (nerdCopter) (2023-10-31) --------- Co-authored-by: Peck07 <28628457+Peck07@users.noreply.github.com> Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> --- make/source.mk | 1 + src/main/drivers/accgyro/accgyro.h | 5 +- src/main/drivers/accgyro/accgyro_mpu.c | 14 + src/main/drivers/accgyro/accgyro_mpu.h | 3 +- src/main/drivers/accgyro/accgyro_spi_bmi270.c | 499 ++++++++++++++++++ src/main/drivers/accgyro/accgyro_spi_bmi270.h | 28 + src/main/drivers/accgyro/gyro_sync.c | 26 +- src/main/drivers/bus_spi.c | 1 + src/main/fc/config.c | 1 + src/main/flight/pid.c | 2 +- src/main/interface/settings.c | 8 +- src/main/pg/bus_spi.c | 3 + src/main/sensors/acceleration.c | 12 + src/main/sensors/acceleration.h | 1 + src/main/sensors/gyro.c | 17 +- src/main/sensors/gyro.h | 1 + src/main/target/common_fc_pre.h | 2 +- 17 files changed, 605 insertions(+), 19 deletions(-) create mode 100644 src/main/drivers/accgyro/accgyro_spi_bmi270.c create mode 100644 src/main/drivers/accgyro/accgyro_spi_bmi270.h diff --git a/make/source.mk b/make/source.mk index ad1a5d0f7a..dd602fab3c 100644 --- a/make/source.mk +++ b/make/source.mk @@ -198,6 +198,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ drivers/accgyro/accgyro_mpu6050.c \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_bmi160.c \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/accgyro/accgyro_spi_icm20689.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h index 2c17f4b2f5..0bcf72738c 100644 --- a/src/main/drivers/accgyro/accgyro.h +++ b/src/main/drivers/accgyro/accgyro.h @@ -33,6 +33,9 @@ #include #endif +#define GYRO_SCALE_2000DPS (2000.0f / (1 << 15)) // 16.384 dps/lsb scalefactor for 2000dps sensors +#define GYRO_SCALE_4000DPS (4000.0f / (1 << 15)) // 8.192 dps/lsb scalefactor for 4000dps sensor + #ifndef MPU_I2C_INSTANCE #define MPU_I2C_INSTANCE I2C_DEVICE #endif @@ -40,7 +43,7 @@ #define GYRO_HARDWARE_LPF_NORMAL 0 #define GYRO_HARDWARE_LPF_1KHZ_SAMPLE 2 -#if defined(USE_GYRO_SPI_ICM42688P) +#if defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI270) #define GYRO_HARDWARE_LPF_EXPERIMENTAL 3 #else #define GYRO_HARDWARE_LPF_EXPERIMENTAL 1 diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 5265e27342..f4b913736e 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -53,6 +53,7 @@ #include "drivers/accgyro/accgyro_mpu6050.h" #include "drivers/accgyro/accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_spi_bmi160.h" +#include "drivers/accgyro/accgyro_spi_bmi270.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" #include "drivers/accgyro/accgyro_spi_icm426xx.h" @@ -404,6 +405,19 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro) { gyro->mpuDetectionResult.sensor = sensor; return true; } +#endif +#ifdef USE_ACCGYRO_BMI270 +#ifndef USE_DUAL_GYRO + spiBusSetInstance(&gyro->bus, BMI270_SPI_INSTANCE); +#endif +#ifdef BMI270_CS_PIN + gyro->bus.busdev_u.spi.csnPin = gyro->bus.busdev_u.spi.csnPin == IO_NONE ? IOGetByTag(IO_TAG(BMI270_CS_PIN)) : gyro->bus.busdev_u.spi.csnPin; +#endif + sensor = bmi270Detect(&gyro->bus); + if (sensor != MPU_NONE) { + gyro->mpuDetectionResult.sensor = sensor; + return true; + } #endif return false; } diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h index aa0f770e29..b85e6d4ca4 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.h +++ b/src/main/drivers/accgyro/accgyro_mpu.h @@ -29,7 +29,7 @@ //#define DEBUG_MPU_DATA_READY_INTERRUPT #if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20649) \ - || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) + || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) #define GYRO_USES_SPI #endif @@ -219,6 +219,7 @@ typedef enum { ICM_42605_SPI, ICM_42688P_SPI, BMI_160_SPI, + BMI_270_SPI, IMUF_9001_SPI, } mpuSensor_e; diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c new file mode 100644 index 0000000000..b7e4749770 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -0,0 +1,499 @@ +/* + * 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_ACCGYRO_BMI270 + +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_spi_bmi270.h" +#include "drivers/bus_spi.h" +#include "drivers/exti.h" +#include "drivers/io.h" +#include "drivers/io_impl.h" +#include "drivers/nvic.h" +#include "drivers/sensor.h" +#include "drivers/time.h" + +// 10 MHz max SPI frequency +#define BMI270_MAX_SPI_CLK_HZ 10000000 + +#define BMI270_FIFO_FRAME_SIZE 6 + +#define BMI270_CONFIG_SIZE 328 + +// Declaration for the device config (microcode) that must be uploaded to the sensor +const uint8_t bmi270_maximum_fifo_config_file[] = { + 0xc8, 0x2e, 0x00, 0x2e, 0x80, 0x2e, 0x1a, 0x00, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, + 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0xc8, 0x2e, 0x00, 0x2e, 0x90, 0x32, 0x21, 0x2e, 0x59, 0xf5, + 0x10, 0x30, 0x21, 0x2e, 0x6a, 0xf5, 0x1a, 0x24, 0x22, 0x00, 0x80, 0x2e, 0x3b, 0x00, 0xc8, 0x2e, 0x44, 0x47, 0x22, + 0x00, 0x37, 0x00, 0xa4, 0x00, 0xff, 0x0f, 0xd1, 0x00, 0x07, 0xad, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, + 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, + 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x80, 0x2e, 0x00, 0xc1, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x11, 0x24, 0xfc, 0xf5, 0x80, 0x30, 0x40, 0x42, 0x50, 0x50, 0x00, 0x30, 0x12, 0x24, 0xeb, + 0x00, 0x03, 0x30, 0x00, 0x2e, 0xc1, 0x86, 0x5a, 0x0e, 0xfb, 0x2f, 0x21, 0x2e, 0xfc, 0xf5, 0x13, 0x24, 0x63, 0xf5, + 0xe0, 0x3c, 0x48, 0x00, 0x22, 0x30, 0xf7, 0x80, 0xc2, 0x42, 0xe1, 0x7f, 0x3a, 0x25, 0xfc, 0x86, 0xf0, 0x7f, 0x41, + 0x33, 0x98, 0x2e, 0xc2, 0xc4, 0xd6, 0x6f, 0xf1, 0x30, 0xf1, 0x08, 0xc4, 0x6f, 0x11, 0x24, 0xff, 0x03, 0x12, 0x24, + 0x00, 0xfc, 0x61, 0x09, 0xa2, 0x08, 0x36, 0xbe, 0x2a, 0xb9, 0x13, 0x24, 0x38, 0x00, 0x64, 0xbb, 0xd1, 0xbe, 0x94, + 0x0a, 0x71, 0x08, 0xd5, 0x42, 0x21, 0xbd, 0x91, 0xbc, 0xd2, 0x42, 0xc1, 0x42, 0x00, 0xb2, 0xfe, 0x82, 0x05, 0x2f, + 0x50, 0x30, 0x21, 0x2e, 0x21, 0xf2, 0x00, 0x2e, 0x00, 0x2e, 0xd0, 0x2e, 0xf0, 0x6f, 0x02, 0x30, 0x02, 0x42, 0x20, + 0x26, 0xe0, 0x6f, 0x02, 0x31, 0x03, 0x40, 0x9a, 0x0a, 0x02, 0x42, 0xf0, 0x37, 0x05, 0x2e, 0x5e, 0xf7, 0x10, 0x08, + 0x12, 0x24, 0x1e, 0xf2, 0x80, 0x42, 0x83, 0x84, 0xf1, 0x7f, 0x0a, 0x25, 0x13, 0x30, 0x83, 0x42, 0x3b, 0x82, 0xf0, + 0x6f, 0x00, 0x2e, 0x00, 0x2e, 0xd0, 0x2e, 0x12, 0x40, 0x52, 0x42, 0x00, 0x2e, 0x12, 0x40, 0x52, 0x42, 0x3e, 0x84, + 0x00, 0x40, 0x40, 0x42, 0x7e, 0x82, 0xe1, 0x7f, 0xf2, 0x7f, 0x98, 0x2e, 0x6a, 0xd6, 0x21, 0x30, 0x23, 0x2e, 0x61, + 0xf5, 0xeb, 0x2c, 0xe1, 0x6f +}; + +#define BMI270_CHIP_ID 0x24 + +// BMI270 registers (not the complete list) +typedef enum { + BMI270_REG_CHIP_ID = 0x00, + BMI270_REG_ERR_REG = 0x02, + BMI270_REG_STATUS = 0x03, + BMI270_REG_ACC_DATA_X_LSB = 0x0C, + BMI270_REG_GYR_DATA_X_LSB = 0x12, + BMI270_REG_SENSORTIME_0 = 0x18, + BMI270_REG_SENSORTIME_1 = 0x19, + BMI270_REG_SENSORTIME_2 = 0x1A, + BMI270_REG_EVENT = 0x1B, + BMI270_REG_INT_STATUS_0 = 0x1C, + BMI270_REG_INT_STATUS_1 = 0x1D, + BMI270_REG_INTERNAL_STATUS = 0x21, + BMI270_REG_TEMPERATURE_LSB = 0x22, + BMI270_REG_TEMPERATURE_MSB = 0x23, + BMI270_REG_FIFO_LENGTH_LSB = 0x24, + BMI270_REG_FIFO_LENGTH_MSB = 0x25, + BMI270_REG_FIFO_DATA = 0x26, + BMI270_REG_ACC_CONF = 0x40, + BMI270_REG_ACC_RANGE = 0x41, + BMI270_REG_GYRO_CONF = 0x42, + BMI270_REG_GYRO_RANGE = 0x43, + BMI270_REG_AUX_CONF = 0x44, + BMI270_REG_FIFO_DOWNS = 0x45, + BMI270_REG_FIFO_WTM_0 = 0x46, + BMI270_REG_FIFO_WTM_1 = 0x47, + BMI270_REG_FIFO_CONFIG_0 = 0x48, + BMI270_REG_FIFO_CONFIG_1 = 0x49, + BMI270_REG_SATURATION = 0x4A, + BMI270_REG_INT1_IO_CTRL = 0x53, + BMI270_REG_INT2_IO_CTRL = 0x54, + BMI270_REG_INT_LATCH = 0x55, + BMI270_REG_INT1_MAP_FEAT = 0x56, + BMI270_REG_INT2_MAP_FEAT = 0x57, + BMI270_REG_INT_MAP_DATA = 0x58, + BMI270_REG_INIT_CTRL = 0x59, + BMI270_REG_INIT_DATA = 0x5E, + BMI270_REG_ACC_SELF_TEST = 0x6D, + BMI270_REG_GYR_SELF_TEST_AXES = 0x6E, + BMI270_REG_PWR_CONF = 0x7C, + BMI270_REG_PWR_CTRL = 0x7D, + BMI270_REG_CMD = 0x7E, +} bmi270Register_e; + +// BMI270 register configuration values +typedef enum { + BMI270_VAL_CMD_SOFTRESET = 0xB6, + BMI270_VAL_CMD_FIFOFLUSH = 0xB0, + BMI270_VAL_PWR_CTRL = 0x0E, // enable gyro, acc and temp sensors + BMI270_VAL_PWR_CONF = 0x02, // disable advanced power save, enable FIFO self-wake + BMI270_VAL_ACC_CONF_ODR800 = 0x0B, // set acc sample rate to 800hz + BMI270_VAL_ACC_CONF_ODR1600 = 0x0C, // set acc sample rate to 1600hz + BMI270_VAL_ACC_CONF_BWP = 0x02, // set acc filter in normal mode + BMI270_VAL_ACC_CONF_HP = 0x01, // set acc in high performance mode + BMI270_VAL_ACC_RANGE_8G = 0x02, // set acc to 8G full scale + BMI270_VAL_ACC_RANGE_16G = 0x03, // set acc to 16G full scale + BMI270_VAL_GYRO_CONF_ODR3200 = 0x0D, // set gyro sample rate to 3200hz + BMI270_VAL_GYRO_CONF_BWP_OSR4 = 0x00, // set gyro filter in OSR4 mode + BMI270_VAL_GYRO_CONF_BWP_OSR2 = 0x01, // set gyro filter in OSR2 mode + BMI270_VAL_GYRO_CONF_BWP_NORM = 0x02, // set gyro filter in normal mode + BMI270_VAL_GYRO_CONF_NOISE_PERF = 0x01, // set gyro in high performance noise mode + BMI270_VAL_GYRO_CONF_FILTER_PERF = 0x01, // set gyro in high performance filter mode + + BMI270_VAL_GYRO_RANGE_2000DPS = 0x08, // set gyro to 2000dps full scale + // for some reason you have to enable the ois_range bit (bit 3) for 2000dps as well + // or else the gyro scale will be 250dps when in prefiltered FIFO mode (not documented in datasheet!) + + BMI270_VAL_INT_MAP_DATA_DRDY_INT1 = 0x04,// enable the data ready interrupt pin 1 + BMI270_VAL_INT_MAP_FIFO_WM_INT1 = 0x02, // enable the FIFO watermark interrupt pin 1 + BMI270_VAL_INT1_IO_CTRL_PINMODE = 0x0A, // active high, push-pull, output enabled, input disabled + BMI270_VAL_FIFO_CONFIG_0 = 0x00, // don't stop when full, disable sensortime frame + BMI270_VAL_FIFO_CONFIG_1 = 0x80, // only gyro data in FIFO, use headerless mode + BMI270_VAL_FIFO_DOWNS = 0x00, // select unfiltered gyro data with no downsampling (6.4KHz samples) + BMI270_VAL_FIFO_WTM_0 = 0x06, // set the FIFO watermark level to 1 gyro sample (6 bytes) + BMI270_VAL_FIFO_WTM_1 = 0x00, // FIFO watermark MSB +} bmi270ConfigValues_e; + +// BMI270 register reads are 16bits with the first byte a "dummy" value 0 +// that must be ignored. The result is in the second byte. +static uint8_t bmi270RegisterRead(const busDevice_t *bus, bmi270Register_e registerId) +{ + uint8_t data[2] = { 0, 0 }; + + if (spiBusReadRegisterBuffer(bus, registerId, data, 2)) { + return data[1]; + } else { + return 0; + } +} + +static void bmi270RegisterWrite(const busDevice_t *bus, bmi270Register_e registerId, uint8_t value, unsigned delayMs) +{ + spiBusWriteRegister(bus, registerId, value); + if (delayMs) { + delay(delayMs); + } +} + +// Toggle the CS to switch the device into SPI mode. +// Device switches initializes as I2C and switches to SPI on a low to high CS transition +static void bmi270EnableSPI(const busDevice_t *bus) +{ + IOLo(bus->busdev_u.spi.csnPin); + delay(1); + IOHi(bus->busdev_u.spi.csnPin); + delay(10); +} + +uint8_t bmi270Detect(const busDevice_t *bus) +{ +#ifndef USE_DUAL_GYRO + IOInit(bus->busdev_u.spi.csnPin, OWNER_MPU_CS, 0); + IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG); + IOHi(bus->busdev_u.spi.csnPin); +#endif + + spiSetDivisor(bus->busdev_u.spi.instance, spiCalculateDivider(BMI270_MAX_SPI_CLK_HZ)); + bmi270EnableSPI(bus); + + if (bmi270RegisterRead(bus, BMI270_REG_CHIP_ID) == BMI270_CHIP_ID) { + return BMI_270_SPI; + } + + return MPU_NONE; +} + +static void bmi270UploadConfig(const busDevice_t *bus) +{ + bmi270RegisterWrite(bus, BMI270_REG_PWR_CONF, 0, 1); + bmi270RegisterWrite(bus, BMI270_REG_INIT_CTRL, 0, 1); + + // Transfer the config file + IOLo(bus->busdev_u.spi.csnPin); + spiTransferByte(bus->busdev_u.spi.instance, BMI270_REG_INIT_DATA); + spiTransfer(bus->busdev_u.spi.instance, bmi270_maximum_fifo_config_file, NULL, sizeof(bmi270_maximum_fifo_config_file)); + IOHi(bus->busdev_u.spi.csnPin); + + delay(10); + bmi270RegisterWrite(bus, BMI270_REG_INIT_CTRL, 1, 1); +} + +static uint8_t getBmiOsrMode() +{ + switch(gyroConfig()->gyro_hardware_lpf) { + case GYRO_HARDWARE_LPF_NORMAL: + return BMI270_VAL_GYRO_CONF_BWP_OSR4; + case GYRO_HARDWARE_LPF_EXPERIMENTAL: + return BMI270_VAL_GYRO_CONF_BWP_OSR2; + } + return 0; +} + +static void bmi270Config(const gyroDev_t *gyro) +{ + const busDevice_t *bus = &gyro->bus; + + // If running in hardware_lpf experimental mode then switch to FIFO-based, + // 6.4KHz sampling, unfiltered data vs. the default 3.2KHz with hardware filtering +#ifdef USE_GYRO_DLPF_EXPERIMENTAL + const bool fifoMode = (gyro->hardware_lpf == GYRO_HARDWARE_LPF_EXPERIMENTAL); +#else + const bool fifoMode = false; +#endif + + // Perform a soft reset to set all configuration to default + // Delay 100ms before continuing configuration + bmi270RegisterWrite(bus, BMI270_REG_CMD, BMI270_VAL_CMD_SOFTRESET, 100); + + // Toggle the chip into SPI mode + bmi270EnableSPI(bus); + + bmi270UploadConfig(bus); + + // Configure the FIFO + if (fifoMode) { + bmi270RegisterWrite(bus, BMI270_REG_FIFO_CONFIG_0, BMI270_VAL_FIFO_CONFIG_0, 1); + bmi270RegisterWrite(bus, BMI270_REG_FIFO_CONFIG_1, BMI270_VAL_FIFO_CONFIG_1, 1); + bmi270RegisterWrite(bus, BMI270_REG_FIFO_DOWNS, BMI270_VAL_FIFO_DOWNS, 1); + bmi270RegisterWrite(bus, BMI270_REG_FIFO_WTM_0, BMI270_VAL_FIFO_WTM_0, 1); + bmi270RegisterWrite(bus, BMI270_REG_FIFO_WTM_1, BMI270_VAL_FIFO_WTM_1, 1); + } + + // Configure the accelerometer + bmi270RegisterWrite(bus, BMI270_REG_ACC_CONF, (BMI270_VAL_ACC_CONF_HP << 7) | (BMI270_VAL_ACC_CONF_BWP << 4) | BMI270_VAL_ACC_CONF_ODR800, 1); + + // Configure the accelerometer full-scale range + bmi270RegisterWrite(bus, BMI270_REG_ACC_RANGE, BMI270_VAL_ACC_RANGE_16G, 1); + + // Configure the gyro + bmi270RegisterWrite(bus, BMI270_REG_GYRO_CONF, (BMI270_VAL_GYRO_CONF_FILTER_PERF << 7) | (BMI270_VAL_GYRO_CONF_NOISE_PERF << 6) | (getBmiOsrMode() << 4) | BMI270_VAL_GYRO_CONF_ODR3200, 1); + + // Configure the gyro full-range scale + bmi270RegisterWrite(bus, BMI270_REG_GYRO_RANGE, BMI270_VAL_GYRO_RANGE_2000DPS, 1); + + // Configure the gyro data ready interrupt + if (fifoMode) { + // Interrupt driven by FIFO watermark level + bmi270RegisterWrite(bus, BMI270_REG_INT_MAP_DATA, BMI270_VAL_INT_MAP_FIFO_WM_INT1, 1); + } else { + // Interrupt driven by data ready + bmi270RegisterWrite(bus, BMI270_REG_INT_MAP_DATA, BMI270_VAL_INT_MAP_DATA_DRDY_INT1, 1); + } + + // Configure the behavior of the INT1 pin + bmi270RegisterWrite(bus, BMI270_REG_INT1_IO_CTRL, BMI270_VAL_INT1_IO_CTRL_PINMODE, 1); + + // Configure the device for performance mode + bmi270RegisterWrite(bus, BMI270_REG_PWR_CONF, BMI270_VAL_PWR_CONF, 1); + + // Enable the gyro, accelerometer and temperature sensor - disable aux interface + bmi270RegisterWrite(bus, BMI270_REG_PWR_CTRL, BMI270_VAL_PWR_CTRL, 1); + + // Flush the FIFO + if (fifoMode) { + bmi270RegisterWrite(bus, BMI270_REG_CMD, BMI270_VAL_CMD_FIFOFLUSH, 1); + } +} + +extiCallbackRec_t bmi270IntCallbackRec; + +#if defined(USE_GYRO_EXTI) && defined(USE_MPU_DATA_READY_SIGNAL) +void bmi270ExtiHandler(extiCallbackRec_t *cb) +{ + gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); + gyro->dataReady = true; +} + +static void bmi270IntExtiInit(gyroDev_t *gyro) +{ + if (gyro->mpuIntExtiTag == IO_TAG_NONE) { + return; + } + + IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag); + + IOInit(mpuIntIO, OWNER_MPU_EXTI, 0); + EXTIHandlerInit(&gyro->exti, bmi270ExtiHandler); + EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING ); + EXTIEnable(mpuIntIO, true); +} +#endif + +static bool bmi270AccRead(accDev_t *acc) +{ + enum { + IDX_REG = 0, + IDX_SKIP, + IDX_ACCEL_XOUT_L, + IDX_ACCEL_XOUT_H, + IDX_ACCEL_YOUT_L, + IDX_ACCEL_YOUT_H, + IDX_ACCEL_ZOUT_L, + IDX_ACCEL_ZOUT_H, + BUFFER_SIZE, + }; + + uint8_t bmi270_rx_buf[BUFFER_SIZE]; + static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_ACC_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0}; + + IOLo(acc->bus.busdev_u.spi.csnPin); + spiTransfer(acc->bus.busdev_u.spi.instance, bmi270_tx_buf, bmi270_rx_buf, BUFFER_SIZE); // receive response + IOHi(acc->bus.busdev_u.spi.csnPin); + + acc->ADCRaw[X] = (int16_t)((bmi270_rx_buf[IDX_ACCEL_XOUT_H] << 8) | bmi270_rx_buf[IDX_ACCEL_XOUT_L]); + acc->ADCRaw[Y] = (int16_t)((bmi270_rx_buf[IDX_ACCEL_YOUT_H] << 8) | bmi270_rx_buf[IDX_ACCEL_YOUT_L]); + acc->ADCRaw[Z] = (int16_t)((bmi270_rx_buf[IDX_ACCEL_ZOUT_H] << 8) | bmi270_rx_buf[IDX_ACCEL_ZOUT_L]); + + return true; +} + +static bool bmi270GyroReadRegister(gyroDev_t *gyro) +{ + enum { + IDX_REG = 0, + IDX_SKIP, + IDX_GYRO_XOUT_L, + IDX_GYRO_XOUT_H, + IDX_GYRO_YOUT_L, + IDX_GYRO_YOUT_H, + IDX_GYRO_ZOUT_L, + IDX_GYRO_ZOUT_H, + BUFFER_SIZE, + }; + + uint8_t bmi270_rx_buf[BUFFER_SIZE]; + static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0}; + + IOLo(gyro->bus.busdev_u.spi.csnPin); + spiTransfer(gyro->bus.busdev_u.spi.instance, bmi270_tx_buf, bmi270_rx_buf, BUFFER_SIZE); // receive response + IOHi(gyro->bus.busdev_u.spi.csnPin); + + gyro->gyroADCRaw[X] = (int16_t)((bmi270_rx_buf[IDX_GYRO_XOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_XOUT_L]); + gyro->gyroADCRaw[Y] = (int16_t)((bmi270_rx_buf[IDX_GYRO_YOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_YOUT_L]); + gyro->gyroADCRaw[Z] = (int16_t)((bmi270_rx_buf[IDX_GYRO_ZOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_ZOUT_L]); + + return true; +} + +#ifdef USE_GYRO_DLPF_EXPERIMENTAL +static bool bmi270GyroReadFifo(gyroDev_t *gyro) +{ + enum { + IDX_REG = 0, + IDX_SKIP, + IDX_FIFO_LENGTH_L, + IDX_FIFO_LENGTH_H, + IDX_GYRO_XOUT_L, + IDX_GYRO_XOUT_H, + IDX_GYRO_YOUT_L, + IDX_GYRO_YOUT_H, + IDX_GYRO_ZOUT_L, + IDX_GYRO_ZOUT_H, + BUFFER_SIZE, + }; + + bool dataRead = false; + static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_FIFO_LENGTH_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + uint8_t bmi270_rx_buf[BUFFER_SIZE]; + + // Burst read the FIFO length followed by the next 6 bytes containing the gyro axis data for + // the first sample in the queue. It's possible for the FIFO to be empty so we need to check the + // length before using the sample. + IOLo(gyro->bus.busdev_u.spi.csnPin); + spiTransfer(gyro->bus.busdev_u.spi.instance, bmi270_tx_buf, bmi270_rx_buf, BUFFER_SIZE); // receive response + IOHi(gyro->bus.busdev_u.spi.csnPin); + + int fifoLength = (uint16_t)((bmi270_rx_buf[IDX_FIFO_LENGTH_H] << 8) | bmi270_rx_buf[IDX_FIFO_LENGTH_L]); + + if (fifoLength >= BMI270_FIFO_FRAME_SIZE) { + + const int16_t gyroX = (int16_t)((bmi270_rx_buf[IDX_GYRO_XOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_XOUT_L]); + const int16_t gyroY = (int16_t)((bmi270_rx_buf[IDX_GYRO_YOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_YOUT_L]); + const int16_t gyroZ = (int16_t)((bmi270_rx_buf[IDX_GYRO_ZOUT_H] << 8) | bmi270_rx_buf[IDX_GYRO_ZOUT_L]); + + // If the FIFO data is invalid then the returned values will be 0x8000 (-32768) (pg. 43 of datasheet). + // This shouldn't happen since we're only using the data if the FIFO length indicates + // that data is available, but this safeguard is needed to prevent bad things in + // case it does happen. + if ((gyroX != INT16_MIN) || (gyroY != INT16_MIN) || (gyroZ != INT16_MIN)) { + gyro->gyroADCRaw[X] = gyroX; + gyro->gyroADCRaw[Y] = gyroY; + gyro->gyroADCRaw[Z] = gyroZ; + dataRead = true; + } + fifoLength -= BMI270_FIFO_FRAME_SIZE; + } + + // If there are additional samples in the FIFO then we don't use those for now and simply + // flush the FIFO. Under normal circumstances we only expect one sample in the FIFO since + // the gyro loop is running at the native sample rate of 6.4KHz. + // However the way the FIFO works in the sensor is that if a frame is partially read then + // it remains in the queue instead of bein removed. So if we ever got into a state where there + // was a partial frame or other unexpected data in the FIFO is may never get cleared and we + // would end up in a lock state of always re-reading the same partial or invalid sample. + if (fifoLength > 0) { + // Partial or additional frames left - flush the FIFO + bmi270RegisterWrite(&gyro->bus, BMI270_REG_CMD, BMI270_VAL_CMD_FIFOFLUSH, 0); + } + + return dataRead; +} +#endif + +static bool bmi270GyroRead(gyroDev_t *gyro) +{ +#ifdef USE_GYRO_DLPF_EXPERIMENTAL + if (gyro->hardware_lpf == GYRO_HARDWARE_LPF_EXPERIMENTAL) { + // running in 6.4KHz FIFO mode + return bmi270GyroReadFifo(gyro); + } else +#endif + { + // running in 3.2KHz register mode + return bmi270GyroReadRegister(gyro); + } +} + +static void bmi270SpiGyroInit(gyroDev_t *gyro) +{ + bmi270Config(gyro); + +#if defined(USE_GYRO_EXTI) && defined(USE_MPU_DATA_READY_SIGNAL) + bmi270IntExtiInit(gyro); +#endif +} + +static void bmi270SpiAccInit(accDev_t *acc) +{ + // sensor is configured during gyro init + acc->acc_1G = 512 * 4; // 16G sensor scale +} + +bool bmi270SpiAccDetect(accDev_t *acc) +{ + if (acc->mpuDetectionResult.sensor != BMI_270_SPI) { + return false; + } + + acc->initFn = bmi270SpiAccInit; + acc->readFn = bmi270AccRead; + + return true; +} + + +bool bmi270SpiGyroDetect(gyroDev_t *gyro) +{ + if (gyro->mpuDetectionResult.sensor != BMI_270_SPI) { + return false; + } + + gyro->initFn = bmi270SpiGyroInit; + gyro->readFn = bmi270GyroRead; + gyro->scale = GYRO_SCALE_2000DPS; + + return true; +} + +// Used to query the status register to determine what event caused the EXTI to fire. +// When in 3.2KHz mode the interrupt is mapped to the data ready state. However the data ready +// trigger will fire for both gyro and accelerometer. So it's necessary to check this register +// to determine which event caused the interrupt. +// When in 6.4KHz mode the interrupt is configured to be the FIFO watermark size of 6 bytes. +// Since in this mode we only put gyro data in the FIFO it's sufficient to check for the FIFO +// watermark reason as an idication of gyro data ready. +uint8_t bmi270InterruptStatus(gyroDev_t *gyro) +{ + return bmi270RegisterRead(&gyro->bus, BMI270_REG_INT_STATUS_1); +} +#endif // USE_ACCGYRO_BMI270 diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.h b/src/main/drivers/accgyro/accgyro_spi_bmi270.h new file mode 100644 index 0000000000..c0ea0495fa --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.h @@ -0,0 +1,28 @@ +/* + * 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 + +#include "drivers/bus.h" + +uint8_t bmi270Detect(const busDevice_t *bus); +bool bmi270SpiAccDetect(accDev_t *acc); +bool bmi270SpiGyroDetect(gyroDev_t *gyro); +uint8_t bmi270InterruptStatus(gyroDev_t *gyro); diff --git a/src/main/drivers/accgyro/gyro_sync.c b/src/main/drivers/accgyro/gyro_sync.c index bc9ad37f27..3653c24d43 100644 --- a/src/main/drivers/accgyro/gyro_sync.c +++ b/src/main/drivers/accgyro/gyro_sync.c @@ -53,16 +53,24 @@ uint32_t gyroSetSampleRate(gyroDev_t *gyro, uint8_t lpf, uint8_t gyroSyncDenomin } gyro->mpuDividerDrops = gyroSyncDenominator - 1; gyro->gyroRateKHz = lpfNoneOr256 ? GYRO_RATE_8_kHz : GYRO_RATE_1_kHz; - //20649 is a weird gyro - if (gyro->mpuDetectionResult.sensor == ICM_20649_SPI) { - gyro->gyroRateKHz = lpfNoneOr256 ? GYRO_RATE_9_kHz : GYRO_RATE_1100_Hz; - } else if (gyro->mpuDetectionResult.sensor == BMI_160_SPI && lpfNoneOr256) { - //brainFPV is also a weird gyro - gyro->gyroRateKHz = GYRO_RATE_3200_Hz; - } else if (gyro_use_32khz) { - //use full 32k - gyro->gyroRateKHz = GYRO_RATE_32_kHz; + + switch (gyro->mpuDetectionResult.sensor) { + case ICM_20649_SPI: //20649 is a weird gyro + gyro->gyroRateKHz = lpfNoneOr256 ? GYRO_RATE_9_kHz : GYRO_RATE_1100_Hz; + break; + case BMI_160_SPI: //brainFPV is also a weird gyro + if (lpfNoneOr256) { gyro->gyroRateKHz = GYRO_RATE_3200_Hz; } + break; + case BMI_270_SPI: //bmi270 + gyro->gyroRateKHz = GYRO_RATE_3200_Hz; + break; + default: + if (gyro_use_32khz) { + //use full 32k + gyro->gyroRateKHz = GYRO_RATE_32_kHz; + } } + // return the targetLooptime (expected cycleTime) return (uint32_t)(gyroSyncDenominator * gyro->gyroRateKHz); } diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 6bddbb9c5b..71a62b210b 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -252,6 +252,7 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) { bus->busdev_u.spi.instance = instance; } +// icm42688p and bmi270 porting uint16_t spiCalculateDivider(uint32_t freq) { #if defined(STM32F4) || defined(STM32G4) || defined(STM32F7) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 5ccab8f8b5..37ca42323d 100644 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -434,6 +434,7 @@ void validateAndFixGyroConfig(void) { samplingTime = 1.0f / 9000.0f; break; case BMI_160_SPI: + case BMI_270_SPI: samplingTime = 0.0003125f; break; default: diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 231c6fa489..be511b02f7 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -86,7 +86,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 2); #ifdef STM32F10X #define PID_PROCESS_DENOM_DEFAULT 1 -#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) +#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) #define PID_PROCESS_DENOM_DEFAULT 1 #else #define PID_PROCESS_DENOM_DEFAULT 2 diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 9af64f98e5..9cedcd3a45 100644 --- a/src/main/interface/settings.c +++ b/src/main/interface/settings.c @@ -109,13 +109,13 @@ const char * const lookupTableAccHardware[] = { "AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", - "ICM42605", "ICM42688P", "BMI160", "ACC_IMUF9001", "FAKE" + "ICM42605", "ICM42688P", "BMI160", "BMI270", "ACC_IMUF9001", "FAKE" }; // sync with gyroSensor_e const char * const lookupTableGyroHardware[] = { "AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689", - "ICM42605", "ICM42688P", "BMI160", "GYRO_IMUF9001", "FAKE" + "ICM42605", "ICM42688P", "BMI160", "BMI270", "GYRO_IMUF9001", "FAKE" }; #if defined(USE_SENSOR_NAMES) || defined(USE_BARO) @@ -252,10 +252,10 @@ static const char * const lookupTableRxSpi[] = { static const char * const lookupTableGyroHardwareLpf[] = { "NORMAL", -#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI270) "OPTION1", "OPTION2", -#if defined(USE_GYRO_SPI_ICM42688P) && defined(USE_GYRO_DLPF_EXPERIMENTAL) // will need bmi270 logic as well +#if ( defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI270) ) && defined(USE_GYRO_DLPF_EXPERIMENTAL) // icm42688p & bmi270 experimental "EXPERIMENTAL", #endif #else diff --git a/src/main/pg/bus_spi.c b/src/main/pg/bus_spi.c index 3b1fcfa7a8..e8e50fc84f 100644 --- a/src/main/pg/bus_spi.c +++ b/src/main/pg/bus_spi.c @@ -100,6 +100,9 @@ ioTag_t preinitIPUList[SPI_PREINIT_IPU_COUNT] = { #ifdef BMI160_CS_PIN IO_TAG(BMI160_CS_PIN), #endif +#ifdef BMI270_CS_PIN + IO_TAG(BMI270_CS_PIN), +#endif #ifdef L3GD20_CS_PIN IO_TAG(L3GD20_CS_PIN), #endif diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 62460a182c..6a45d357b4 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -43,6 +43,7 @@ #include "drivers/accgyro/accgyro_mpu6050.h" #include "drivers/accgyro/accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_spi_bmi160.h" +#include "drivers/accgyro/accgyro_spi_bmi270.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" #include "drivers/accgyro/accgyro_spi_icm426xx.h" @@ -299,6 +300,17 @@ bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse) { } FALLTHROUGH; #endif +#ifdef USE_ACCGYRO_BMI270 + case ACC_BMI270: + if (bmi270SpiAccDetect(dev)) { + accHardware = ACC_BMI270; +#ifdef ACC_BMI270_ALIGN + dev->accAlign = ACC_BMI270_ALIGN; +#endif + break; + } + FALLTHROUGH; +#endif #if defined(USE_ACC_SPI_ICM42605) || defined(USE_ACC_SPI_ICM42688P) case ACC_ICM42605: case ACC_ICM42688P: diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index b448d2419b..5b132c53f6 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -50,6 +50,7 @@ typedef enum { ACC_ICM42605, ACC_ICM42688P, ACC_BMI160, + ACC_BMI270, ACC_IMUF9001, ACC_FAKE } accelerationSensor_e; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index eefea7e341..9ec6a642fc 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -44,6 +44,7 @@ #include "drivers/accgyro/accgyro_mpu6050.h" #include "drivers/accgyro/accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_spi_bmi160.h" +#include "drivers/accgyro/accgyro_spi_bmi270.h" #include "drivers/accgyro/accgyro_spi_icm20649.h" #include "drivers/accgyro/accgyro_spi_icm20689.h" #include "drivers/accgyro/accgyro_spi_icm426xx.h" @@ -211,7 +212,7 @@ static void gyroInitLowpassFilterLpf(gyroSensor_t *gyroSensor, int slot, int typ #ifdef STM32F10X #define GYRO_SYNC_DENOM_DEFAULT 8 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \ - || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) + || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) #define GYRO_SYNC_DENOM_DEFAULT 1 #else #define GYRO_SYNC_DENOM_DEFAULT 3 @@ -537,6 +538,17 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) { } FALLTHROUGH; #endif +#ifdef USE_ACCGYRO_BMI270 + case GYRO_BMI270: + if (bmi270SpiGyroDetect(dev)) { + gyroHardware = GYRO_BMI270; +#ifdef GYRO_BMI270_ALIGN + dev->gyroAlign = GYRO_BMI270_ALIGN; +#endif + break; + } + FALLTHROUGH; +#endif #ifdef USE_GYRO_IMUF9001 case GYRO_IMUF9001: if (imufSpiGyroDetect(dev)) { @@ -566,7 +578,7 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev) { static bool gyroInitSensor(gyroSensor_t *gyroSensor) { gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr; #if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) \ - || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160) + || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_GYRO_IMUF9001) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) mpuDetect(&gyroSensor->gyroDev); mpuResetFn = gyroSensor->gyroDev.mpuConfiguration.resetFn; // must be set after mpuDetect #endif @@ -611,6 +623,7 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor) { case GYRO_MPU3050: case GYRO_L3GD20: case GYRO_BMI160: + case GYRO_BMI270: case GYRO_MPU6000: case GYRO_MPU6500: case GYRO_MPU9250: diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index b81475a75c..671d7b7cbd 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -56,6 +56,7 @@ typedef enum { GYRO_ICM42605, GYRO_ICM42688P, GYRO_BMI160, + GYRO_BMI270, GYRO_IMUF9001, GYRO_FAKE } gyroSensor_e; diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h index 426ec9b767..4d378c10ac 100644 --- a/src/main/target/common_fc_pre.h +++ b/src/main/target/common_fc_pre.h @@ -229,5 +229,5 @@ #define USE_CMS_GPS_RESCUE_MENU #endif -// ICM42688P define +// ICM42688P & BMI270 experimental define #define USE_GYRO_DLPF_EXPERIMENTAL From 218da79e563de518cd4fa203ffa20c1283c63345 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 1 Nov 2023 10:22:34 -0500 Subject: [PATCH 28/37] [target] BETAFPVF411 - add BMI270 (#937) --- src/main/target/BETAFPVF411/target.h | 7 +++++++ src/main/target/BETAFPVF411/target.mk | 1 + 2 files changed, 8 insertions(+) diff --git a/src/main/target/BETAFPVF411/target.h b/src/main/target/BETAFPVF411/target.h index 68172fdc56..ddd244caef 100644 --- a/src/main/target/BETAFPVF411/target.h +++ b/src/main/target/BETAFPVF411/target.h @@ -34,6 +34,13 @@ #define USE_SPI #define USE_SPI_DEVICE_1 +#define USE_SPI_GYRO +#define USE_ACCGYRO_BMI270 +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 +#define ACC_BMI270_ALIGN CW90_DEG +#define GYRO_BMI270_ALIGN CW90_DEG + #define SPI1_SCK_PIN PA5 #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 diff --git a/src/main/target/BETAFPVF411/target.mk b/src/main/target/BETAFPVF411/target.mk index 3971d0ca39..ab77872afb 100644 --- a/src/main/target/BETAFPVF411/target.mk +++ b/src/main/target/BETAFPVF411/target.mk @@ -4,6 +4,7 @@ FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ From fa26c36cfc8769385dd0e27ebdfaf30b32add4eb Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 11:29:04 -0500 Subject: [PATCH 29/37] [target] FLYWOOF411_5IN1_AIO - add BMI270 (#938) --- src/main/target/FLYWOOF411_5IN1_AIO/target.h | 8 +++++- src/main/target/FLYWOOF411_5IN1_AIO/target.mk | 25 ++++++++++--------- 2 files changed, 20 insertions(+), 13 deletions(-) diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.h b/src/main/target/FLYWOOF411_5IN1_AIO/target.h index 5e93cd6460..33c06dde11 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.h +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.h @@ -65,10 +65,16 @@ #define USE_ACC_SPI_ICM42688P #define ICM42688P_SPI_INSTANCE SPI1 -#define ICM42688P_CS_PIN PB2 +#define ICM42688P_CS_PIN PA4 #define ACC_ICM42688P_ALIGN CW0_DEG_FLIP #define GYRO_ICM42688P_ALIGN CW0_DEG_FLIP +#define USE_SPI_GYRO +#define BMI270_SPI_INSTANCE SPI1 +#define BMI270_CS_PIN PA4 +#define ACC_BMI270_ALIGN CW0_DEG_FLIP +#define GYRO_BMI270_ALIGN CW0_DEG_FLIP + // *************** Baro ************************** #define USE_I2C diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk index 19d3a639b7..a0f0b8aff2 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk @@ -3,22 +3,23 @@ F411_TARGETS += $(TARGET) FEATURES += VCP TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_icm20689.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_spi_bmi270.c \ + drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/max7456.c \ drivers/rx/rx_cc2500.c \ - rx/cc2500_common.c \ + rx/cc2500_common.c \ rx/cc2500_frsky_shared.c \ rx/cc2500_frsky_d.c \ - rx/cc2500_frsky_x.c \ - rx/cc2500_redpine.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_redpine.c \ rx/cc2500_sfhss.c\ drivers/rx/rx_a7105.c \ - drivers/light_ws2811strip.c + drivers/light_ws2811strip.c From 0d1a56a399d3455ca43081b676d00d4504fbd80a Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 11:31:15 -0500 Subject: [PATCH 30/37] [target] FOXEERF745_AIO_V2 (BMI270) (#939) --- .../target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk | 0 src/main/target/FOXEERF745_AIO/target.h | 16 ++++++++++++++++ src/main/target/FOXEERF745_AIO/target.mk | 5 +++-- 3 files changed, 19 insertions(+), 2 deletions(-) create mode 100644 src/main/target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk diff --git a/src/main/target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk b/src/main/target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/FOXEERF745_AIO/target.h b/src/main/target/FOXEERF745_AIO/target.h index bd56acc8ef..80c7fb0d14 100644 --- a/src/main/target/FOXEERF745_AIO/target.h +++ b/src/main/target/FOXEERF745_AIO/target.h @@ -21,7 +21,13 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "FOXE" + #define TARGET_MANUFACTURER_IDENTIFIER "FOXE" + + #if defined(FOXEERF745_AIO_V2) + #define USBD_PRODUCT_STRING "FOXEERF745_AIO_V2" + #else #define USBD_PRODUCT_STRING "FOXEERF745_AIO" + #endif #define LED0_PIN PC13 @@ -55,6 +61,16 @@ //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP //#define MAG_ALIGN CW180_DEG //not sure if this command will work or if should be more specific to mag + #if defined(FOXEERF745_AIO_V2) + //BMI270 + #define USE_SPI_GYRO + #define USE_ACCGYRO_BMI270 + #define BMI270_CS_PIN PA15 + #define BMI270_SPI_INSTANCE SPI3 + #define ACC_BMI270_ALIGN CW180_DEG + #define GYRO_BMI270_ALIGN CW180_DEG + #endif + #define USE_BARO #define USE_BARO_BMP280 #define BARO_I2C_INSTANCE (I2CDEV_1) diff --git a/src/main/target/FOXEERF745_AIO/target.mk b/src/main/target/FOXEERF745_AIO/target.mk index e4faff73d9..01b1543813 100644 --- a/src/main/target/FOXEERF745_AIO/target.mk +++ b/src/main/target/FOXEERF745_AIO/target.mk @@ -2,11 +2,12 @@ F7X5XG_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_lis3mdl.c \ + drivers/compass/compass_lis3mdl.c \ drivers/light_ws2811strip.c \ drivers/max7456.c From 731894ae28f701601a044effc1cd3bdd314e2da3 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 11:33:07 -0500 Subject: [PATCH 31/37] [target] IFLIGHT_F745_AIO_V2 add BMI270 (#940) --- src/main/target/IFLIGHT_F745_AIO_V2/target.h | 2 +- src/main/target/IFLIGHT_F745_AIO_V2/target.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.h b/src/main/target/IFLIGHT_F745_AIO_V2/target.h index 6eec787ed9..e771a75672 100644 --- a/src/main/target/IFLIGHT_F745_AIO_V2/target.h +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.h @@ -39,7 +39,7 @@ #define USE_DUAL_GYRO #define USE_SPI_GYRO -//#define USE_ACCGYRO_BMI270 +#define USE_ACCGYRO_BMI270 #define USE_GYRO_SPI_MPU6000 #define USE_ACC_SPI_MPU6000 diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.mk b/src/main/target/IFLIGHT_F745_AIO_V2/target.mk index 525f68127c..7cfd60c081 100644 --- a/src/main/target/IFLIGHT_F745_AIO_V2/target.mk +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.mk @@ -2,12 +2,12 @@ F7X5XG_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_mpu.c \ drivers/barometer/barometer_ms5611.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/light_ws2811strip.c \ From c1ef73d4dbbce800952159586d26e5370462a599 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 15:31:12 -0500 Subject: [PATCH 32/37] [target] NBD_INFINITYAIOV2PRO (BMI270) (#941) --- src/main/target/NBD_INFINITYAIOV2PRO/target.c | 37 ++++ src/main/target/NBD_INFINITYAIOV2PRO/target.h | 160 ++++++++++++++++++ .../target/NBD_INFINITYAIOV2PRO/target.mk | 13 ++ 3 files changed, 210 insertions(+) create mode 100644 src/main/target/NBD_INFINITYAIOV2PRO/target.c create mode 100644 src/main/target/NBD_INFINITYAIOV2PRO/target.h create mode 100644 src/main/target/NBD_INFINITYAIOV2PRO/target.mk diff --git a/src/main/target/NBD_INFINITYAIOV2PRO/target.c b/src/main/target/NBD_INFINITYAIOV2PRO/target.c new file mode 100644 index 0000000000..b0d2fbf100 --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2PRO/target.c @@ -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 . + */ + +#include + +#include "platform.h" +#include "drivers/io.h" + +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0 ), // LED_STRIP, + + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // M1 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), // M2 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 0, 0 ), // M3 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, 0, 0 ), // M4 +}; diff --git a/src/main/target/NBD_INFINITYAIOV2PRO/target.h b/src/main/target/NBD_INFINITYAIOV2PRO/target.h new file mode 100644 index 0000000000..6b871d43ef --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2PRO/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 + +#define TARGET_MANUFACTURER_IDENTIFIER "NEBD" +#define USBD_PRODUCT_STRING "NBD_INFINITYAIOV2PRO" + +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + +#define LED0_PIN PC0 + +#define USE_BEEPER +#define BEEPER_PIN PD13 +#define BEEPER_INVERTED + +#define USE_SPI_GYRO +#define USE_ACCGYRO_BMI270 +#define BMI270_CS_PIN PE11 +#define BMI270_SPI_INSTANCE SPI4 +#define ACC_BMI270_ALIGN CW270_DEG +#define GYRO_BMI270_ALIGN CW270_DEG + +// dual gyro +#define USE_DUAL_GYRO + +#define USE_EXTI //REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +// gyro 1 +#define GYRO_1_CS_PIN PE11 +#define GYRO_1_SPI_INSTANCE SPI4 +#define GYRO_1_EXTI_PIN PB1 +#define GYRO_1_ALIGN CW270_DEG +#define ACC_1_ALIGN CW270_DEG + +// gyro 2 +#define GYRO_2_CS_PIN PB12 +#define GYRO_2_SPI_INSTANCE SPI2 +#define GYRO_2_EXTI_PIN PD0 +#define GYRO_2_ALIGN CW270_DEG +#define ACC_2_ALIGN CW270_DEG + +#define USE_VCP +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PB7 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 + +#define USE_UART7 +#define UART7_TX_PIN PE8 + +#define USE_UART8 +#define UART8_RX_PIN PE0 +#define UART8_TX_PIN PE1 + +#define SERIAL_PORT_COUNT 7 //VCP, USART1, USART2, USART3, UART5, USART7, UART8 + +#define USE_ESC_SENSOR + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PD6 + +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 + +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI3 +#define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz +#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASH +#define USE_FLASHFS +#define USE_FLASH_W25Q128FV //official +#define FLASH_CS_PIN PB0 +#define FLASH_SPI_INSTANCE SPI1 + +#define USE_FLASH_M25P16 // testing // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_FLASH_W25M // testing // 1Gb NAND flash support +#define USE_FLASH_W25M512 // testing // 16, 32, 64 or 128MB Winbond stacked die support +#define USE_FLASH_W25Q // testing // 512Kb (256Kb x 2 stacked) NOR flash support + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE_1 (I2CDEV_1) +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_ADC +#define VBAT_ADC_PIN PC1 +#define CURRENT_METER_ADC_PIN PC2 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define CURRENT_METER_SCALE_DEFAULT 100 + +#define BEEPER_PWM_HZ 5400 + +#define USE_LED_STRIP +#define LED_STRIP_PIN PA9 + +#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 DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL + +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/NBD_INFINITYAIOV2PRO/target.mk b/src/main/target/NBD_INFINITYAIOV2PRO/target.mk new file mode 100644 index 0000000000..ff6b7c6818 --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2PRO/target.mk @@ -0,0 +1,13 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c \ + drivers/compass/compass_fake.c \ + drivers/compass/compass_ak8963.c \ + drivers/compass/compass_ak8975.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/compass/compass_qmc5883l.c \ From 2bb2a72c3dce7f6ade3028fcfb74a8cd5ae36398 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 15:32:15 -0500 Subject: [PATCH 33/37] [target] SKYSTARSF7HD add BMI270 (#942) --- src/main/target/SKYSTARSF7HD/target.h | 7 +++++++ src/main/target/SKYSTARSF7HD/target.mk | 3 ++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/main/target/SKYSTARSF7HD/target.h b/src/main/target/SKYSTARSF7HD/target.h index bf68dc5fc4..31d1d6f3fa 100644 --- a/src/main/target/SKYSTARSF7HD/target.h +++ b/src/main/target/SKYSTARSF7HD/target.h @@ -53,6 +53,13 @@ #define USE_ACC +#define USE_SPI_GYRO +#define USE_ACCGYRO_BMI270 +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG + #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 diff --git a/src/main/target/SKYSTARSF7HD/target.mk b/src/main/target/SKYSTARSF7HD/target.mk index 1b54266132..1f9b3af4ff 100644 --- a/src/main/target/SKYSTARSF7HD/target.mk +++ b/src/main/target/SKYSTARSF7HD/target.mk @@ -2,6 +2,7 @@ F7X2RE_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/barometer/barometer_bmp085.c \ @@ -9,5 +10,5 @@ TARGET_SRC = \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ - drivers/light_ws2811strip.c \ + drivers/light_ws2811strip.c \ drivers/max7456.c From 01155c0cebd50672c33c7a68d25d6e6c4ec5379b Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Thu, 2 Nov 2023 15:34:56 -0500 Subject: [PATCH 34/37] [target] SKYSTARSF7HDPRO (#943) Co-authored-by: BeauBrewski <85623381+BeauBrewski@users.noreply.github.com> --- src/main/target/SKYSTARSF7HDPRO/config.c | 36 ++++ src/main/target/SKYSTARSF7HDPRO/target.c | 41 +++++ src/main/target/SKYSTARSF7HDPRO/target.h | 207 ++++++++++++++++++++++ src/main/target/SKYSTARSF7HDPRO/target.mk | 16 ++ 4 files changed, 300 insertions(+) create mode 100644 src/main/target/SKYSTARSF7HDPRO/config.c create mode 100644 src/main/target/SKYSTARSF7HDPRO/target.c create mode 100644 src/main/target/SKYSTARSF7HDPRO/target.h create mode 100644 src/main/target/SKYSTARSF7HDPRO/target.mk diff --git a/src/main/target/SKYSTARSF7HDPRO/config.c b/src/main/target/SKYSTARSF7HDPRO/config.c new file mode 100644 index 0000000000..30086932e3 --- /dev/null +++ b/src/main/target/SKYSTARSF7HDPRO/config.c @@ -0,0 +1,36 @@ +/* + * 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" + +#define USE_TARGET_CONFIG + +#include "io/serial.h" +#include "pg/pinio.h" +#include "pg/piniobox.h" +#include "target.h" + + +void targetConfiguration(void) { + pinioBoxConfigMutable()->permanentId[0] = 40; + pinioConfigMutable()->config[0] = 129; +} diff --git a/src/main/target/SKYSTARSF7HDPRO/target.c b/src/main/target/SKYSTARSF7HDPRO/target.c new file mode 100644 index 0000000000..d993355657 --- /dev/null +++ b/src/main/target/SKYSTARSF7HDPRO/target.c @@ -0,0 +1,41 @@ +/* + * 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/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0, 0 ), // PPM IN + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), // S1_OUT – UP2-1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), // S2_OUT – UP2-1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0 ), // S3_OUT – UP2-5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0 ), // S4_OUT – UP2-5 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0 ), // FC CAM – DMA1_ST7 + + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – DMA1_ST6 +}; diff --git a/src/main/target/SKYSTARSF7HDPRO/target.h b/src/main/target/SKYSTARSF7HDPRO/target.h new file mode 100644 index 0000000000..19c0c2e753 --- /dev/null +++ b/src/main/target/SKYSTARSF7HDPRO/target.h @@ -0,0 +1,207 @@ +/* + * 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 + +#define USE_TARGET_CONFIG + +#define TARGET_MANUFACTURER_IDENTIFIER "SKST" +#define USBD_PRODUCT_STRING "SKST7HDPRO" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" + +// ******* LEDs and BEEPER ******** + +#define LED0_PIN PC15 +#define LED1_PIN PC14 + +#define USE_BEEPER +#define BEEPER_PIN PB2 +#define BEEPER_INVERTED + +//#define ENABLE_DSHOT_DMAR true + +#define USE_PINIO +#define PINIO1_PIN PA14 // Bluetooth mode control, PB0 is connected to the 36 pin (P2.0) of the Bluetooth chip. Replace PB0 with the pin for your flight control and 36-pin connection + +#define USE_CAMERA_CONTROL +#define CAMERA_CONTROL_PIN PA8 // define dedicated camera osd pin + + +// ******* GYRO and ACC ******** + +#define USE_DUAL_GYRO +#define USE_EXTI +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_2_EXTI_PIN PC0 +#define MPU_INT_EXTI + +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define GYRO_2_CS_PIN PC13 +#define GYRO_2_SPI_INSTANCE SPI1 + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_SPI_GYRO +#define USE_ACCGYRO_BMI270 + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 + +#define GYRO_1_ALIGN CW90_DEG_FLIP +#define ACC_1_ALIGN CW90_DEG_FLIP + +#define GYRO_2_ALIGN CW0_DEG +#define ACC_2_ALIGN CW0_DEG + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW +#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 + +// *************** Baro ************************ + +#define USE_SPI + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define DEFAULT_BARO_SPI_BMP280 +#define BMP280_SPI_INSTANCE SPI2 +#define BMP280_CS_PIN PB1 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define MAG_I2C_INSTANCE (I2CDEV_1) + +// ******* SERIAL ******** + +#define USE_VCP + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 + +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define SERIAL_PORT_COUNT 9 //VCP, UART1-UART6 , 2 x Soft Serial + +// ******* SPI ******** + +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** + +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define ADC2_DMA_STREAM DMA2_Stream3 + +#define VBAT_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define CURRENT_METER_ADC_PIN PC3 + +// ******* OSD ******** + +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_CLK ( SPI_CLOCK_STANDARD ) +#define MAX7456_RESTORE_CLK ( SPI_CLOCK_FAST ) + +//******* FLASH ******** + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define FLASH_CS_PIN PA15 +#define FLASH_SPI_INSTANCE SPI3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// ******* FEATURES ******** + +#define USE_OSD + +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define CURRENT_METER_SCALE_DEFAULT 290 + + +#define USE_ESCSERIAL + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3)| TIM_N(4) | TIM_N(8) ) diff --git a/src/main/target/SKYSTARSF7HDPRO/target.mk b/src/main/target/SKYSTARSF7HDPRO/target.mk new file mode 100644 index 0000000000..6d549c15d0 --- /dev/null +++ b/src/main/target/SKYSTARSF7HDPRO/target.mk @@ -0,0 +1,16 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms5611.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c From aaa46e69e2e89d2c97cc2a1d157fafd2ade3ba9d Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Sat, 4 Nov 2023 16:14:22 -0500 Subject: [PATCH 35/37] [target] TMOTORF7 update; add ICM42688P and BMI270 (#944) * [target] TMOTORF7 update; add ICM42688P and BMI270 --- src/main/target/TMTR_TMOTORF7/target.c | 21 ++++++----- src/main/target/TMTR_TMOTORF7/target.h | 50 +++++++++++++++++++------ src/main/target/TMTR_TMOTORF7/target.mk | 7 +++- 3 files changed, 55 insertions(+), 23 deletions(-) diff --git a/src/main/target/TMTR_TMOTORF7/target.c b/src/main/target/TMTR_TMOTORF7/target.c index 847810cf45..ecaa7704b1 100644 --- a/src/main/target/TMTR_TMOTORF7/target.c +++ b/src/main/target/TMTR_TMOTORF7/target.c @@ -25,15 +25,16 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 8 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), - - DEF_TIM(TIM2, CH1, PA15, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_PPM, 0, 0), // ppm + DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // cam ctrl + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led }; diff --git a/src/main/target/TMTR_TMOTORF7/target.h b/src/main/target/TMTR_TMOTORF7/target.h index 1353cbead9..20ce09a1c2 100644 --- a/src/main/target/TMTR_TMOTORF7/target.h +++ b/src/main/target/TMTR_TMOTORF7/target.h @@ -20,9 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "TMR7" -#define USBD_PRODUCT_STRING "TMOTORF7" #define TARGET_MANUFACTURER_IDENTIFIER "TMTR" +#define USBD_PRODUCT_STRING "TMOTORF7" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID #define LED0_PIN PB2 @@ -35,7 +37,7 @@ #define USE_PINIO #define PINIO1_PIN PC14 #define USE_PINIOBOX - +#define PINIO1_BOX 40 #define ENABLE_DSHOT_DMAR true @@ -44,21 +46,44 @@ #define USE_MPU_DATA_READY_SIGNAL #define USE_GYRO +#define USE_ACC + #define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 + #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_INSTANCE SPI1 -#define ACC_MPU6000_ALIGN CW0_DEG -#define GYRO_MPU6000_ALIGN CW0_DEG +#define ACC_MPU6000_ALIGN CW0_DEG +#define GYRO_MPU6000_ALIGN CW0_DEG -#define USE_ACC -#define USE_ACC_SPI_MPU6000 -#define USE_ACC_SPI_MPU6500 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 +#define ACC_MPU6500_ALIGN CW0_DEG +#define GYRO_MPU6500_ALIGN CW0_DEG + +#define USE_SPI_GYRO +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 +#define ACC_BMI270_ALIGN CW0_DEG +#define GYRO_BMI270_ALIGN CW0_DEG + +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 +#define ACC_ICM42688P_ALIGN CW0_DEG +#define GYRO_ICM42688P_ALIGN CW0_DEG #define USE_BARO #define USE_BARO_SPI_BMP280 #define DEFAULT_BARO_SPI_BMP280 #define BMP280_SPI_INSTANCE SPI3 #define BMP280_CS_PIN PC15 +#define BARO_SPI_INSTANCE SPI3 +#define BARO_CS_PIN PC15 #define USE_MAG #define USE_MAG_HMC5883 @@ -133,20 +158,21 @@ #define VBAT_ADC_PIN PC1 #define CURRENT_METER_ADC_PIN PC2 #define RSSI_ADC_PIN PC3 +#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0 #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC -#define SERIALRX_PROVIDER SERIALRX_SBUS +//#define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_UART5 -//#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1 +#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1 // soft UART?? #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES ( FEATURE_OSD ) +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) #define TARGET_IO_PORTA ( 0xffff ) #define TARGET_IO_PORTB ( 0xffff ) #define TARGET_IO_PORTC ( 0xffff ) #define TARGET_IO_PORTD ( 0x0004 ) -#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USABLE_TIMER_CHANNEL_COUNT 11 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(11) ) diff --git a/src/main/target/TMTR_TMOTORF7/target.mk b/src/main/target/TMTR_TMOTORF7/target.mk index 15077cfbd3..c023c93328 100644 --- a/src/main/target/TMTR_TMOTORF7/target.mk +++ b/src/main/target/TMTR_TMOTORF7/target.mk @@ -1,10 +1,15 @@ F7X2RE_TARGETS += $(TARGET) FEATURES = VCP ONBOARDFLASH TARGET_SRC = \ + drivers/accgyro/accgyro_spi_bmi270.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ - drivers/max7456.c + drivers/light_led.h \ + drivers/light_ws2811strip.c \ + drivers/pinio.c \ + drivers/max7456.c \ From 3fd716c1a09a2a38539dd477c7d5345a75253939 Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 8 Nov 2023 09:57:52 -0600 Subject: [PATCH 36/37] [target] GEPRCF411_AIO add BMI270 and ICM42688P (#946) --- src/main/target/GEPRCF411_AIO/target.h | 16 +++++++++++++++- src/main/target/GEPRCF411_AIO/target.mk | 12 +++++++----- 2 files changed, 22 insertions(+), 6 deletions(-) diff --git a/src/main/target/GEPRCF411_AIO/target.h b/src/main/target/GEPRCF411_AIO/target.h index 2ebb2a9272..8f0ac9d3b9 100644 --- a/src/main/target/GEPRCF411_AIO/target.h +++ b/src/main/target/GEPRCF411_AIO/target.h @@ -60,6 +60,20 @@ #define USE_ACC_SPI_MPU6500 #define ACC_MPU6500_ALIGN CW180_DEG +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define ACC_ICM42688P_ALIGN CW180_DEG +#define GYRO_ICM42688P_ALIGN CW180_DEG +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 + +#define USE_SPI_GYRO +#define USE_ACCGYRO_BMI270 +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 + // *************** Baro ************************** #define USE_I2C @@ -131,7 +145,7 @@ #define USE_ESCSERIAL #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_SOFTSERIAL) #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC #define CURRENT_METER_SCALE_DEFAULT 100 diff --git a/src/main/target/GEPRCF411_AIO/target.mk b/src/main/target/GEPRCF411_AIO/target.mk index 21fb3eb49f..10c401603f 100644 --- a/src/main/target/GEPRCF411_AIO/target.mk +++ b/src/main/target/GEPRCF411_AIO/target.mk @@ -2,14 +2,16 @@ F411_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ + drivers/accgyro/accgyro_spi_bmi270.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c\ - drivers/light_ws2811strip.c\ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c\ + drivers/light_ws2811strip.c\ drivers/max7456.c From 86a7a0d26ccf5dc04c083427b64390cb05982c3a Mon Sep 17 00:00:00 2001 From: nerdCopter <56646290+nerdCopter@users.noreply.github.com> Date: Wed, 8 Nov 2023 14:42:23 -0600 Subject: [PATCH 37/37] [target] add SPEEDYBEEF7V3 with BMI270 (#948) --- src/main/target/SPBE_SPEEDYBEEF7V3/target.c | 46 ++++++ src/main/target/SPBE_SPEEDYBEEF7V3/target.h | 165 +++++++++++++++++++ src/main/target/SPBE_SPEEDYBEEF7V3/target.mk | 18 ++ 3 files changed, 229 insertions(+) create mode 100644 src/main/target/SPBE_SPEEDYBEEF7V3/target.c create mode 100644 src/main/target/SPBE_SPEEDYBEEF7V3/target.h create mode 100644 src/main/target/SPBE_SPEEDYBEEF7V3/target.mk diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.c b/src/main/target/SPBE_SPEEDYBEEF7V3/target.c new file mode 100644 index 0000000000..2e21c085f3 --- /dev/null +++ b/src/main/target/SPBE_SPEEDYBEEF7V3/target.c @@ -0,0 +1,46 @@ +/* + * This file is part of EmuFlight. It is derived from Betaflight. + * + * This is 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. + * + * This software 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 software. + * + * If not, see . + */ + +// This resource file generated using https://github.com/nerdCopter/target-convert +// Commit: 4cb7ad1 + +#include +#include "platform.h" +#include "drivers/io.h" +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // ppm; dma 0 assumed, please verify + DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // cam ctrl +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.h b/src/main/target/SPBE_SPEEDYBEEF7V3/target.h new file mode 100644 index 0000000000..8de845f81d --- /dev/null +++ b/src/main/target/SPBE_SPEEDYBEEF7V3/target.h @@ -0,0 +1,165 @@ +/* + * This file is part of EmuFlight. It is derived from Betaflight. + * + * This is 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. + * + * This software 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 software. + * + * If not, see . + */ + +// This resource file generated using https://github.com/nerdCopter/target-convert +// Commit: 4cb7ad1 + manual edits for SDCard, UART5, etc. + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "SPBE" +#define USBD_PRODUCT_STRING "SPEEDYBEEF7V3" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_BARO +#define USE_SPI_GYRO + +#define USE_VCP +#define USE_OSD + +#define USE_LED +#define LED0_PIN PA14 +#define LED1_PIN PA13 +#define LED_STRIP_PIN PC8 +#define USE_BEEPER +#define BEEPER_PIN PC13 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PA0 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define GYRO_1_ALIGN CW270_DEG_FLIP +#define ACC_1_ALIGN CW270_DEG_FLIP +#define GYRO_1_CS_PIN PB2 +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PC4 + +#define USE_DUAL_GYRO +#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_2 + +#define GYRO_2_ALIGN CW0_DEG_FLIP +#define ACC_2_ALIGN CW0_DEG_FLIP +#define GYRO_2_CS_PIN PC15 +#define GYRO_2_EXTI_PIN PC3 +#define GYRO_2_SPI_INSTANCE SPI1 + +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_SPI_GYRO +#define ACC_BMI270_ALIGN CW270_DEG_FLIP +#define GYRO_BMI270_ALIGN CW270_DEG_FLIP +#define BMI270_CS_PIN PB2 +#define BMI270_SPI_INSTANCE SPI1 + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +// note: UART5 NONE, but still need to define USE_UART5 and add +1 to serial-count. +#define USE_UART5 +#define SERIAL_PORT_COUNT 7 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE (I2CDEV_1) +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define BARO_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +//#define USE_FLASH //breaks CLI resources (need support in .mk? or not valid at all?) +#define FLASH_CS_PIN PD2 +#define FLASH_SPI_INSTANCE SPI3 + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define USE_SDCARD_SDIO +#define SDCARD_SPI_CS_PIN PD2 +#define SDCARD_SPI_INSTANCE SPI3 +#define SDCARD_DMA_CHANNEL 0 +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5 //# SPI_MOSI 3: DMA1 Stream 5 Channel 0 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 + +#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_INSTANCE SPI2 + +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC2 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC0 +#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define DEFAULT_CURRENT_METER_SCALE 490 + +#define ENABLE_DSHOT_DMAR true + +#define PINIO1_PIN PC9 +#define PINIO1_CONFIG 129 +#define PINIO1_BOX 0 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL + +#define USABLE_TIMER_CHANNEL_COUNT 11 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) + +// notice - this file was programmatically generated and may be incomplete. + diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.mk b/src/main/target/SPBE_SPEEDYBEEF7V3/target.mk new file mode 100644 index 0000000000..c97ce2f4ed --- /dev/null +++ b/src/main/target/SPBE_SPEEDYBEEF7V3/target.mk @@ -0,0 +1,18 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP SDCARD + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_bmi270.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ + +# notice - this file was programmatically generated and may be incomplete. +# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc. especially mag/baro + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 4cb7ad1 +