diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index ed938545a9..54922794f6 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -159,6 +159,7 @@ jobs: echo "outputs.shortsha: ${{ needs.build.outputs.shortsha }}" echo "outputs.artfact: ${{ needs.build.outputs.artifact }}" echo "outputs.artfact: ${{ needs.build.outputs.version }}" + echo "NOW=$(date +'%Y%m%d.%H%M%S')" >> $GITHUB_ENV continue-on-error: true - name: download artifacts @@ -181,7 +182,7 @@ jobs: repo: dev-unstable owner: emuflight token: ${{ secrets.NC_PAT_EMUF }} - tag: "hex-${{ github.run_number }}" + tag: "${{ env.NOW }}-hex" draft: true prerelease: true allowUpdates: true @@ -213,7 +214,7 @@ jobs: repo: dev-master owner: emuflight token: ${{ secrets.NC_PAT_EMUF }} - tag: "hex-${{ github.run_number }}" + tag: "${{ env.NOW }}-hex" draft: true prerelease: true allowUpdates: true diff --git a/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c b/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c index 4aa38e731f..a1bf0317ee 100644 --- a/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c +++ b/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c @@ -423,6 +423,8 @@ void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) /* Get the PLLM value */ pllm = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wduplicated-branches" if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE) { /* Get the I2S source clock value */ @@ -433,6 +435,7 @@ void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) i2sclk = (uint32_t)(((HSI_VALUE / pllm) * plln) / pllr); } #endif /* I2S_EXTERNAL_CLOCK_VAL */ +#pragma GCC diagnostic pop /* Compute the Real divider depending on the MCLK output state, with a floating point */ if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) diff --git a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c index 4d9e318453..b3d1033aee 100644 --- a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c +++ b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c @@ -248,6 +248,8 @@ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) return HAL_ERROR; } +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wduplicated-branches" if(huart->Init.HwFlowCtl != UART_HWCONTROL_NONE) { /* Check the parameters */ @@ -258,6 +260,7 @@ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) /* Check the parameters */ assert_param(IS_UART_INSTANCE(huart->Instance)); } +#pragma GCC diagnostic pop if(huart->gState == HAL_UART_STATE_RESET) { diff --git a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c index c3ee209cc0..05d33296ce 100644 --- a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c +++ b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c @@ -817,7 +817,7 @@ HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, uin count32b = (len + 3) / 4; for (i = 0; i < count32b; i++, src += 4) { - USBx_DFIFO(ch_ep_num) = *((__packed uint32_t *)src); + USBx_DFIFO((uint32_t)ch_ep_num) = *((uint32_t *)src); } } return HAL_OK; @@ -843,7 +843,7 @@ void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len) for ( i = 0; i < count32b; i++, dest += 4 ) { - *(__packed uint32_t *)dest = USBx_DFIFO(0); + *(uint32_t *)dest = USBx_DFIFO(0); } return ((void *)dest); diff --git a/make/source.mk b/make/source.mk index ad1a5d0f7a..e12e19aa7f 100644 --- a/make/source.mk +++ b/make/source.mk @@ -139,6 +139,7 @@ COMMON_SRC = \ io/dashboard.c \ io/displayport_max7456.c \ io/displayport_msp.c \ + io/displayport_hdzero_osd.c \ io/displayport_oled.c \ io/displayport_srxl.c \ io/displayport_crsf.c \ @@ -198,6 +199,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/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 8ee2428c8d..436871abb4 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]); @@ -1179,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); @@ -1226,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, @@ -1239,6 +1244,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); @@ -1266,6 +1272,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 diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index c775c222e4..f5259d23b5 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -66,6 +66,7 @@ // For VISIBLE* #include "io/osd.h" #include "io/rcdevice_cam.h" +#include "pg/vcd.h" #include "rx/rx.h" @@ -329,7 +330,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row) buff[0] = 0x0; if ((p->type == OME_Submenu) && p->func && (p->flags & OPTSTRING)) { // Special case of sub menu entry with optional value display. - char *str = ((CMSMenuOptFuncPtr)p->func)(); + char *str = ((CMSMenuOptFuncPtr)(long)p->func)(); strncpy( buff, str, CMS_DRAW_BUFFER_LEN); } strncat(buff, ">", CMS_DRAW_BUFFER_LEN); @@ -597,9 +598,19 @@ void cmsMenuOpen(void) { } else { smallScreen = false; linesPerMenuItem = 1; - leftMenuColumn = 2; +#if defined(USE_HDZERO_OSD) + if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30)) + { leftMenuColumn = HDINDENT + 2; } + else +#endif + { leftMenuColumn = SDINDENT + 2; } #ifdef CMS_OSD_RIGHT_ALIGNED_VALUES - rightMenuColumn = pCurrentDisplay->cols - 2; +#if defined(USE_HDZERO_OSD) + if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30)) + { rightMenuColumn = pCurrentDisplay->cols - 2 - HDINDENT; } + else +#endif + { rightMenuColumn = pCurrentDisplay->cols - 2; } #else rightMenuColumn = pCurrentDisplay->cols - CMS_DRAW_BUFFER_LEN; #endif @@ -634,7 +645,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) { currentCtx.menu = NULL; if (exitType == CMS_EXIT_SAVEREBOOT) { displayClearScreen(pDisplay); - displayWrite(pDisplay, 5, 3, "REBOOTING..."); + displayWrite(pDisplay, (pCurrentDisplay->cols % 2) - 6, 3, "REBOOTING..."); displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing? stopMotors(); stopPwmAllMotors(); diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 56adfed277..84f11531c3 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -140,7 +140,7 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr) { return 0; } displayClearScreen(pDisplay); - displayWrite(pDisplay, 5, 3, "ERASING FLASH..."); + displayWrite(pDisplay, (pCurrentDisplay->cols % 2) - 7, 3, "ERASING FLASH..."); displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing? flashfsEraseCompletely(); while (!flashfsIsReady()) { diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index a8f3804735..50c0bfc589 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; @@ -487,13 +493,19 @@ 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; 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; @@ -515,17 +527,22 @@ 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; 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; @@ -547,13 +564,19 @@ 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; 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; @@ -575,19 +598,23 @@ 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 }, #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 +736,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 +754,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 +775,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 +796,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/cms/cms_menu_vtx_smartaudio.c b/src/main/cms/cms_menu_vtx_smartaudio.c index 77622df9e7..319da7d40e 100644 --- a/src/main/cms/cms_menu_vtx_smartaudio.c +++ b/src/main/cms/cms_menu_vtx_smartaudio.c @@ -492,7 +492,7 @@ static OSD_Entry saCmsMenuConfigEntries[] = { { "OP MODEL", OME_TAB, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, DYNAMIC }, { "FSEL MODE", OME_TAB, saCmsConfigFreqModeByGvar, &saCmsEntFselMode, DYNAMIC }, { "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode, 0 }, - { "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING }, + { "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)(long)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING }, #ifdef USE_EXTENDED_CMS_MENUS { "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats, 0 }, #endif /* USE_EXTENDED_CMS_MENUS */ @@ -534,7 +534,7 @@ static OSD_Entry saCmsMenuFreqModeEntries[] = { { "- SMARTAUDIO -", OME_Label, NULL, NULL, 0 }, { "", OME_Label, NULL, saCmsStatusString, DYNAMIC }, - { "FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsUserFreqGetString, &saCmsMenuUserFreq, OPTSTRING }, + { "FREQ", OME_Submenu, (CMSEntryFuncPtr)(long)saCmsUserFreqGetString, &saCmsMenuUserFreq, OPTSTRING }, { "POWER", OME_TAB, saCmsConfigPowerByGvar, &saCmsEntPower, 0 }, { "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence, 0 }, { "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 }, diff --git a/src/main/common/bitarray.c b/src/main/common/bitarray.c index 8884146fbb..3c523c1baa 100644 --- a/src/main/common/bitarray.c +++ b/src/main/common/bitarray.c @@ -51,3 +51,53 @@ void bitArrayCopy(void *array, unsigned from, unsigned to) { bitArrayClr(array, to); } } + +void bitArrayClrAll(bitarrayElement_t *array, size_t size) +{ + memset(array, 0, size); +} + +__attribute__((always_inline)) static inline uint8_t __CTZ(uint32_t val) +{ + // __builtin_ctz is not defined for zero, since it's arch + // dependant. However, in ARM it gets translated to a + // rbit and then a clz, making it return 32 for zero on ARM. + // For other architectures, explicitely implement the same + // semantics. +#ifdef __arm__ + uint8_t zc; + __asm__ volatile ("rbit %1, %1\n\t" + "clz %0, %1" + : "=r" (zc) + : "r" (val) ); + return zc; +#else + // __builtin_clz is not defined for zero, since it's arch + // dependant. Make it return 32 like ARM's CLZ. + return val ? __builtin_ctz(val) : 32; +#endif +} + +int bitArrayFindFirstSet(const bitarrayElement_t *array, unsigned start, size_t size) +{ + const uint32_t *ptr = (uint32_t*)array; + const uint32_t *end = ptr + (size / 4); + const uint32_t *p = ptr + start / (8 * 4); + + if (p < end) { + int ret; + // First iteration might need to mask some bits + uint32_t mask = 0xFFFFFFFF << (start % (8 * 4)); + if ((ret = __CTZ(*p & mask)) != 32) { + return (((char *)p) - ((char *)ptr)) * 8 + ret; + } + p++; + while (p < end) { + if ((ret = __CTZ(*p)) != 32) { + return (((char *)p) - ((char *)ptr)) * 8 + ret; + } + p++; + } + } + return -1; +} \ No newline at end of file diff --git a/src/main/common/bitarray.h b/src/main/common/bitarray.h index 13fafe5550..eaa64b3905 100644 --- a/src/main/common/bitarray.h +++ b/src/main/common/bitarray.h @@ -20,8 +20,21 @@ #pragma once +typedef uint32_t bitarrayElement_t; + bool bitArrayGet(const void *array, unsigned bit); void bitArraySet(void *array, unsigned bit); void bitArrayClr(void *array, unsigned bit); void bitArrayXor(void *dest, size_t size, void *op1, void *op2); void bitArrayCopy(void *array, unsigned from, unsigned to); +void bitArrayClrAll(bitarrayElement_t *array, size_t size); +// Returns the first set bit with pos >= start_bit, or -1 if all bits +// are zero. Note that size must indicate the size of array in bytes. +// In most cases, you should use the BITARRAY_FIND_FIRST_SET() macro +// to call this function. +int bitArrayFindFirstSet(const bitarrayElement_t *array, unsigned start_bit, size_t size); + +#define BITARRAY_DECLARE(name, bits) bitarrayElement_t name[(bits + 31) / 32] +#define BITARRAY_SET_ALL(array) bitArraySetAll(array, sizeof(array)) +#define BITARRAY_CLR_ALL(array) bitArrayClrAll(array, sizeof(array)) +#define BITARRAY_FIND_FIRST_SET(array, start_bit) bitArrayFindFirstSet(array, start_bit, sizeof(array)) \ No newline at end of file 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..0bcf72738c 100644 --- a/src/main/drivers/accgyro/accgyro.h +++ b/src/main/drivers/accgyro/accgyro.h @@ -33,17 +33,28 @@ #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 #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) || defined(USE_ACCGYRO_BMI270) +#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 +102,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..f4b913736e 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -53,8 +53,10 @@ #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" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -365,6 +367,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); @@ -377,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 550f05fe81..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_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) #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,7 +216,10 @@ typedef enum { ICM_20608_SPI, ICM_20649_SPI, ICM_20689_SPI, + 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/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c new file mode 100644 index 0000000000..0b284fcee7 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -0,0 +1,401 @@ +/* + * 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 + +// 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) +#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 = 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); + + // 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/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/beesign.c b/src/main/drivers/beesign.c index ea6bfeee53..a84e6997c1 100644 --- a/src/main/drivers/beesign.c +++ b/src/main/drivers/beesign.c @@ -101,10 +101,13 @@ static uint8_t beesignCRC(const beesign_frame_t *pPackage) { return crc; } +// compiler reports unused +/* static uint8_t beesignChkID(uint8_t id) { UNUSED(id); return BEESIGN_OK; } +*/ uint8_t beesignReceive(uint8_t **pRcvFrame) { if (!receiveFrameValid) { @@ -608,7 +611,7 @@ bool checkBeesignSerialPort(void) { void beesignUpdate(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); - if (checkBeesignSerialPort) { + if (checkBeesignSerialPort()) { #ifdef USE_OSD_BEESIGN static uint32_t beesignTaskCounter = 0; static uint32_t beesignSendNextCounterPoint = 0; diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 93cec8510a..71a62b210b 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -251,4 +251,33 @@ void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance) { bus->bustype = BUSTYPE_SPI; bus->busdev_u.spi.instance = instance; } + +// icm42688p and bmi270 porting +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 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); +} + #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/drivers/display_font_metadata.c b/src/main/drivers/display_font_metadata.c new file mode 100644 index 0000000000..6bf01c383e --- /dev/null +++ b/src/main/drivers/display_font_metadata.c @@ -0,0 +1,11 @@ +#include "drivers/display_font_metadata.h" +#include "drivers/osd.h" + +bool displayFontMetadataUpdateFromCharacter(displayFontMetadata_t *metadata, const osdCharacter_t *chr) +{ + if (chr && FONT_CHR_IS_METADATA(chr)) { + metadata->version = chr->data[5]; + return true; + } + return false; +} diff --git a/src/main/drivers/display_font_metadata.h b/src/main/drivers/display_font_metadata.h new file mode 100644 index 0000000000..961c6b0751 --- /dev/null +++ b/src/main/drivers/display_font_metadata.h @@ -0,0 +1,24 @@ +#pragma once + +#include +#include + +typedef struct osdCharacter_s osdCharacter_t; + +typedef struct displayFontMetadata_s { + uint8_t version; + uint16_t charCount; +} displayFontMetadata_t; + +// 'E', 'M', 'U', 'F' +#define FONT_CHR_IS_METADATA(chr) ((chr)->data[0] == 'E' && \ + (chr)->data[1] == 'M' && \ + (chr)->data[2] == 'U' && \ + (chr)->data[3] == 'F') + +#define FONT_METADATA_CHR_INDEX 255 +// Used for runtime detection of display drivers that might +// support 256 or 512 characters. +#define FONT_METADATA_CHR_INDEX_2ND_PAGE 256 + +bool displayFontMetadataUpdateFromCharacter(displayFontMetadata_t *metadata, const osdCharacter_t *chr); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 6a0767a153..56dd22c9b9 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -492,7 +492,7 @@ uint32_t softSerialTxBytesFree(const serialPort_t *instance) { return 0; } softSerial_t *s = (softSerial_t *)instance; - uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1); + uint32_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1); return (s->port.txBufferSize - 1) - bytesUsed; } 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/fc/fc_init.c b/src/main/fc/fc_init.c index 1c7396a33a..22a4447479 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -115,6 +115,7 @@ #include "rx/spektrum.h" #include "io/beeper.h" +#include "io/displayport_hdzero_osd.h" #include "io/displayport_max7456.h" #include "io/displayport_srxl.h" #include "io/serial.h" @@ -508,12 +509,25 @@ void init(void) { if (feature(FEATURE_OSD)) { #if defined(USE_OSD_BEESIGN) // If there is a beesign for the OSD then use it - osdDisplayPort = beesignDisplayPortInit(vcdProfile()); -#elif defined(USE_MAX7456) + if (!osdDisplayPort) { + osdDisplayPort = beesignDisplayPortInit(vcdProfile()); + } +#endif +#if defined(USE_HDZERO_OSD) + if (!osdDisplayPort) { + osdDisplayPort = hdzeroOsdDisplayPortInit(); + } +#endif +#if defined(USE_MAX7456) // If there is a max7456 chip for the OSD then use it - osdDisplayPort = max7456DisplayPortInit(vcdProfile()); -#elif defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT) // OSD over MSP; not supported (yet) - osdDisplayPort = displayPortMspInit(); + if (!osdDisplayPort) { + osdDisplayPort = max7456DisplayPortInit(vcdProfile()); + } +#endif +#if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT) // OSD over MSP; not supported (yet) + if (!osdDisplayPort) { + osdDisplayPort = displayPortMspInit(); + } #endif // osdInit will register with CMS by itself. osdInit(osdDisplayPort); diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 12831714bf..121e5b702a 100644 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -74,6 +74,7 @@ #include "io/gps.h" #include "io/ledstrip.h" #include "io/osd.h" +#include "io/displayport_hdzero_osd.h" #include "io/piniobox.h" #include "io/serial.h" #include "io/transponder_ir.h" @@ -159,6 +160,11 @@ static void taskHandleSerial(timeUs_t currentTimeUs) { bool evaluateMspData = osdSlaveIsLocked ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;; #endif mspSerialProcess(evaluateMspData, mspFcProcessCommand, mspFcProcessReply); + +#ifdef USE_HDZERO_OSD + // Capture HDZero messages to determine if VTX is connected + hdzeroOsdSerialProcess(mspFcProcessCommand); +#endif } static void taskBatteryAlerts(timeUs_t currentTimeUs) { diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index bb6f1fbdbb..e5e7601ab6 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -84,12 +84,10 @@ extern bool linearThrustEnabled; 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) -#define PID_PROCESS_DENOM_DEFAULT 1 -#else +#if defined(STM32F3) || defined(STM32F411xE) #define PID_PROCESS_DENOM_DEFAULT 2 +#else +#define PID_PROCESS_DENOM_DEFAULT 1 #endif #ifndef DEFAULT_PIDS_ROLL @@ -235,7 +233,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]; @@ -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) @@ -669,7 +671,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) { @@ -809,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/interface/cli.c b/src/main/interface/cli.c index 80bac75d60..75879e5fae 100644 --- a/src/main/interface/cli.c +++ b/src/main/interface/cli.c @@ -990,7 +990,7 @@ static void cliSerial(char *cmdline) { ptr = nextArg(ptr); if (ptr) { val = atoi(ptr); - portConfig.functionMask = val & 0xFFFF; + portConfig.functionMask = val & 0xFFFFFFFF; validArgumentCount++; } for (int i = 0; i < 4; i ++) { diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index b3aebb427d..bdffb85b36 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1084,7 +1084,7 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) { continue; }; sbufWriteU8(dst, serialConfig()->portConfigs[i].identifier); - sbufWriteU16(dst, serialConfig()->portConfigs[i].functionMask); + sbufWriteU32(dst, serialConfig()->portConfigs[i].functionMask); sbufWriteU8(dst, serialConfig()->portConfigs[i].msp_baudrateIndex); sbufWriteU8(dst, serialConfig()->portConfigs[i].gps_baudrateIndex); sbufWriteU8(dst, serialConfig()->portConfigs[i].telemetry_baudrateIndex); @@ -1194,20 +1194,37 @@ 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); //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 +1236,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 @@ -2197,7 +2219,7 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { } break; case MSP_SET_CF_SERIAL_CONFIG: { - uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4); + uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint32_t) + (sizeof(uint8_t) * 4); if (dataSize % portConfigSize != 0) { return MSP_RESULT_ERROR; } @@ -2209,7 +2231,7 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { return MSP_RESULT_ERROR; } portConfig->identifier = identifier; - portConfig->functionMask = sbufReadU16(src); + portConfig->functionMask = sbufReadU32(src); portConfig->msp_baudrateIndex = sbufReadU8(src); portConfig->gps_baudrateIndex = sbufReadU8(src); portConfig->telemetry_baudrateIndex = sbufReadU8(src); diff --git a/src/main/interface/msp_protocol.h b/src/main/interface/msp_protocol.h index 6b062f5387..8716c30f0c 100644 --- a/src/main/interface/msp_protocol.h +++ b/src/main/interface/msp_protocol.h @@ -64,7 +64,7 @@ // API VERSION #define API_VERSION_MAJOR 1 // increment when major changes are made -#define API_VERSION_MINOR 51 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release) +#define API_VERSION_MINOR 53 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release) #define API_VERSION_LENGTH 2 diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c index 0b6664170c..3b7d50938c 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", "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", - "BMI160", "GYRO_IMUF9001", "FAKE" + "ICM42605", "ICM42688P", "BMI160", "BMI270", "GYRO_IMUF9001", "FAKE" }; #if defined(USE_SENSOR_NAMES) || defined(USE_BARO) @@ -245,15 +245,23 @@ static const char * const lookupTableRxSpi[] = { "FLYSKY", "FLYSKY_2A", "KN", - "SFHSS", + "SFHSS", "REDPINE" }; #endif static const char * const lookupTableGyroHardwareLpf[] = { "NORMAL", +#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_ACCGYRO_BMI270) ) && defined(USE_GYRO_DLPF_EXPERIMENTAL) // icm42688p & bmi270 experimental + "EXPERIMENTAL", +#endif +#else "EXPERIMENTAL", "1KHZ_SAMPLING" +#endif }; #ifdef USE_32K_CAPABLE_GYRO @@ -285,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", }; @@ -359,7 +368,7 @@ static const char * const lookupTableRescueSanityType[] = { #ifdef USE_MAX7456 static const char * const lookupTableVideoSystem[] = { - "AUTO", "PAL", "NTSC" + "AUTO", "PAL", "NTSC", "HD" }; #endif // USE_MAX7456 @@ -385,6 +394,10 @@ static const char *const lookupTableMixerImplType[] = { "LEGACY", "SMOOTH", "2PASS" }; +static const char *const lookupTableDynNotchAxisType[] = { + "RP", "RPY" +}; + #define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) } const lookupTableEntry_t lookupTables[] = { @@ -474,6 +487,7 @@ const lookupTableEntry_t lookupTables[] = { LOOKUP_TABLE_ENTRY(lookupTableOsdLogoOnArming), #endif LOOKUP_TABLE_ENTRY(lookupTableMixerImplType), + LOOKUP_TABLE_ENTRY(lookupTableDynNotchAxisType), }; #undef LOOKUP_TABLE_ENTRY @@ -495,10 +509,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) }, @@ -545,6 +561,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) }, @@ -855,9 +872,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..e8a8269834 100644 --- a/src/main/interface/settings.h +++ b/src/main/interface/settings.h @@ -112,6 +112,7 @@ typedef enum { TABLE_OSD_LOGO_ON_ARMING, #endif TABLE_MIXER_IMPL_TYPE, + TABLE_DYN_NOTCH_AXIS_TYPE, LOOKUP_TABLE_COUNT } lookupTableIndex_e; diff --git a/src/main/io/displayport_hdzero_osd.c b/src/main/io/displayport_hdzero_osd.c new file mode 100644 index 0000000000..5cd0b22f2a --- /dev/null +++ b/src/main/io/displayport_hdzero_osd.c @@ -0,0 +1,423 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include + +#include "platform.h" + +#define FILE_COMPILE_FOR_SPEED _Pragma("GCC optimize(\"Ofast\")") + +#include "drivers/display_font_metadata.h" +FILE_COMPILE_FOR_SPEED + +//#define HDZERO_STATS + +#if defined(USE_OSD) && defined(USE_HDZERO_OSD) +#include "common/utils.h" +#include "common/printf.h" +#include "common/time.h" +#include "common/bitarray.h" + +#include "drivers/display.h" +#include "drivers/max7456_symbols.h" + +#include "interface/msp_protocol.h" +#include "io/serial.h" +#include "msp/msp_serial.h" + +#include "displayport_hdzero_osd.h" + +#define FONT_VERSION 3 + +#define MSP_CLEAR_SCREEN 2 +#define MSP_WRITE_STRING 3 +#define MSP_DRAW_SCREEN 4 +#define MSP_SET_OPTIONS 5 +//#define DRAW_FREQ_DENOM 4 // 60Hz +#define DRAW_FREQ_DENOM 8 // 30Hz +#define TX_BUFFER_SIZE 1024 +#define VTX_TIMEOUT 1000 // 1 second timer + +static mspProcessCommandFnPtr mspProcessCommand; +static mspPort_t hdZeroMspPort; +static displayPort_t hdZeroOsdDisplayPort; +static bool vtxSeen, vtxActive, vtxReset; +static timeMs_t vtxHeartbeat; + +// HD screen size +#define ROWS 18 +#define COLS 50 +#define SCREENSIZE (ROWS*COLS) +static uint8_t screen[SCREENSIZE]; +static BITARRAY_DECLARE(fontPage, SCREENSIZE); // font page for each character on the screen +static BITARRAY_DECLARE(dirty, SCREENSIZE); // change status for each character on the screen +static bool screenCleared; + +extern uint8_t cliMode; + +#ifdef HDZERO_STATS +static uint32_t dataSent; +static uint8_t resetCount; +#endif + +static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int len) +{ + UNUSED(displayPort); + + int sent = 0; + + if (!cliMode && vtxActive) { + sent = mspSerialPushPort(cmd, subcmd, len, &hdZeroMspPort, MSP_V1); + } + +#ifdef HDZERO_STATS + dataSent += sent; +#endif + + return sent; +} + +static void checkVtxPresent(void) +{ + if (vtxActive && (millis()-vtxHeartbeat) > VTX_TIMEOUT) { + vtxActive = false; + } +} + +static int setHdMode(displayPort_t *displayPort) +{ + checkVtxPresent(); + uint8_t subcmd[] = { MSP_SET_OPTIONS, 0, 1 }; // font selection, mode (SD/HD) + return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); +} + +static void hdZeroInit(void) +{ + memset(screen, SYM_BLANK, sizeof(screen)); + BITARRAY_CLR_ALL(fontPage); + BITARRAY_CLR_ALL(dirty); +} + +static int clearScreen(displayPort_t *displayPort) +{ + uint8_t subcmd[] = { MSP_CLEAR_SCREEN }; + + hdZeroInit(); + setHdMode(displayPort); + screenCleared = true; + return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); +} + +static int setChar(const uint16_t pos, const uint16_t c) +{ + if (pos < SCREENSIZE) { + uint8_t ch = c & 0xFF; + bool page = (c >> 8); + if (screen[pos] != ch || bitArrayGet(fontPage, pos) != page) { + screen[pos] = ch; + (page) ? bitArraySet(fontPage, pos) : bitArrayClr(fontPage, pos); + bitArraySet(dirty, pos); + } + } + return 0; +} + +static int writeChar(displayPort_t *displayPort, uint8_t col, uint8_t row, uint8_t c) +{ + UNUSED(displayPort); + + return setChar((row * COLS) + col, c); +} + +static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string) +{ + UNUSED(displayPort); + + uint16_t pos = (row * COLS) + col; + while (*string) { + setChar(pos++, *string++); + } + return 0; +} + +#ifdef HDZERO_STATS +static void printStats(displayPort_t *displayPort, uint32_t updates) +{ + static timeMs_t lastTime; + static uint32_t maxDataSent, maxBufferUsed, maxUpdates; + timeMs_t currentTime = millis(); + char lineBuffer[100]; + + if (updates > maxUpdates) { + maxUpdates = updates; // updates sent per displayWrite + } + + uint32_t bufferUsed = TX_BUFFER_SIZE - serialTxBytesFree(hdZeroMspPort.port); + if (bufferUsed > maxBufferUsed) { + maxBufferUsed = bufferUsed; // serial buffer used after displayWrite + } + + uint32_t diff = (currentTime - lastTime); + if (diff > 1000) { // Data sampled in 1 second + if (dataSent > maxDataSent) { + maxDataSent = dataSent; // bps (max 11520 allowed) + } + + dataSent = 0; + lastTime = currentTime; + } + + + tfp_sprintf(lineBuffer, "R:%2d %4ld %5ld(%5ld) U:%2ld(%2ld) B:%3ld(%4ld,%4ld)", resetCount, (millis()-vtxHeartbeat), + dataSent, maxDataSent, updates, maxUpdates, bufferUsed, maxBufferUsed, hdZeroMspPort.port->txBufferSize); + writeString(displayPort, 0, 17, lineBuffer, 0); +} +#endif + +/** + * Write only changed characters to the VTX + */ +static int drawScreen(displayPort_t *displayPort) // 250Hz +{ + static uint8_t counter = 0; + + if ((counter++ % DRAW_FREQ_DENOM) == 0) { + uint8_t subcmd[COLS + 4]; + uint8_t updateCount = 0; + subcmd[0] = MSP_WRITE_STRING; + + int next = BITARRAY_FIND_FIRST_SET(dirty, 0); + while (next >= 0) { + // Look for sequential dirty characters on the same line for the same font page + int pos = next; + uint8_t row = pos / COLS; + uint8_t col = pos % COLS; + int endOfLine = row * COLS + COLS; + bool page = bitArrayGet(fontPage, pos); + + uint8_t len = 4; + do { + bitArrayClr(dirty, pos); + subcmd[len++] = screen[pos++]; + + if (bitArrayGet(dirty, pos)) { + next = pos; + } + } while (next == pos && next < endOfLine && bitArrayGet(fontPage, next) == page); + + subcmd[1] = row; + subcmd[2] = col; + subcmd[3] = page; + output(displayPort, MSP_DISPLAYPORT, subcmd, len); + updateCount++; + next = BITARRAY_FIND_FIRST_SET(dirty, pos); + } + + if (updateCount > 0 || screenCleared) { + if (screenCleared) { + screenCleared = false; + } + subcmd[0] = MSP_DRAW_SCREEN; + output(displayPort, MSP_DISPLAYPORT, subcmd, 1); + } + +#ifdef HDZERO_STATS + printStats(displayPort, updateCount); +#endif + checkVtxPresent(); + + if (vtxReset) { +#ifdef HDZERO_STATS + resetCount++; +#endif + clearScreen(displayPort); + vtxReset = false; + } + } + + return 0; +} + +static void resync(displayPort_t *displayPort) +{ + displayPort->rows = ROWS; + displayPort->cols = COLS; + setHdMode(displayPort); +} + +static int screenSize(const displayPort_t *displayPort) +{ + UNUSED(displayPort); + return SCREENSIZE; +} + +static uint32_t txBytesFree(const displayPort_t *displayPort) +{ + UNUSED(displayPort); + return mspSerialTxBytesFree(); +} + +//Commented out as compiler reports unused. +//static bool getFontMetadata(displayFontMetadata_t *metadata, const displayPort_t *displayPort) +//{ +// UNUSED(displayPort); +// metadata->charCount = 512; +// metadata->version = FONT_VERSION; +// return true; +//} + +static bool isTransferInProgress(const displayPort_t *displayPort) +{ + UNUSED(displayPort); + return false; +} + +//Commented out as compiler reports unused. +//static bool isReady(displayPort_t *displayPort) +//{ +// UNUSED(displayPort); +// return vtxActive; +//} + +static int grab(displayPort_t *displayPort) +{ + UNUSED(displayPort); + return 0; +} + +static int heartbeat(displayPort_t *displayPort) +{ + UNUSED(displayPort); + return 0; +} + +static int release(displayPort_t *displayPort) +{ + UNUSED(displayPort); + return 0; +} + +static const displayPortVTable_t hdzeroOsdVTable = { + .grab = grab, + .release = release, + .clearScreen = clearScreen, + .drawScreen = drawScreen, + .screenSize = screenSize, + .writeString = writeString, + .writeChar = writeChar, + .isTransferInProgress = isTransferInProgress, + .heartbeat = heartbeat, + .resync = resync, + .txBytesFree = txBytesFree, +}; + +bool hdzeroOsdSerialInit(void) +{ + static volatile uint8_t txBuffer[TX_BUFFER_SIZE]; + memset(&hdZeroMspPort, 0, sizeof(mspPort_t)); + + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_HDZERO_OSD); + if (portConfig) { + // serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL, + // baudRates[portConfig->peripheral_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); + serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL, + baudRates[BAUD_115200], MODE_RXTX, SERIAL_NOT_INVERTED); + + if (port) { + // Use a bigger TX buffer size to accommodate the configuration menus + port->txBuffer = txBuffer; + port->txBufferSize = TX_BUFFER_SIZE; + port->txBufferTail = 0; + port->txBufferHead = 0; + + resetMspPort(&hdZeroMspPort, port); + + return true; + } + } + + return false; +} + +displayPort_t* hdzeroOsdDisplayPortInit(void) +{ + if (hdzeroOsdSerialInit()) { + hdZeroInit(); + displayInit(&hdZeroOsdDisplayPort, &hdzeroOsdVTable); + return &hdZeroOsdDisplayPort; + } + return NULL; +} + +/* + * Intercept MSP processor. + * VTX sends an MSP command every 125ms or so. + * VTX will have be marked as not ready if no commands received within VTX_TIMEOUT. + */ +static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) +{ + if (vtxSeen && !vtxActive) { + vtxReset = true; + } + + vtxSeen = vtxActive = true; + vtxHeartbeat = millis(); + + //Commented out as compiler reports unused. + //sbuf_t *dst = &reply->buf; + + const uint8_t cmdMSP = cmd->cmd; + reply->cmd = cmd->cmd; + + //Apparently no longer required as HDZero will send the MSP/EEPROM value of "EMUF" fc_variant + //if (cmdMSP == MSP_FC_VARIANT) { + // //We advertise as EMUF on this port for the prettier font + // sbufWriteData(dst, "EMUF", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH); + // return MSP_RESULT_ACK; + //} + + // #define MSP_SET_VTXTABLE_BAND 227 + // #define MSP_SET_VTXTABLE_POWERLEVEL 228 + // MSP_IMUF_CONFIG 227 -> MSP_SET_VTXTABLE_BAND (in betaflight) + // MSP_SET_IMUF_CONFIG 228 -> MSP_SET_VTXTABLE_POWERLEVEL (in betaflight) + if (cmdMSP == 227 || cmdMSP == 228) { + // We don't have VTX Tables so we just drop the packet and send ACK + return MSP_RESULT_ACK; + } + + // Process MSP command + return mspProcessCommand(cmd, reply, mspPostProcessFn); +} + +void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn) +{ + if (hdZeroMspPort.port) { + mspProcessCommand = mspProcessCommandFn; + mspSerialProcessOnePort(&hdZeroMspPort, MSP_SKIP_NON_MSP_DATA, hdZeroProcessMspCommand); + } +} + +#endif // USE_HDZERO_OSD diff --git a/src/main/io/displayport_hdzero_osd.h b/src/main/io/displayport_hdzero_osd.h new file mode 100644 index 0000000000..2c00245421 --- /dev/null +++ b/src/main/io/displayport_hdzero_osd.h @@ -0,0 +1,34 @@ + +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include "osd.h" +#include "msp/msp_serial.h" + +typedef struct displayPort_s displayPort_t; + +displayPort_t *hdzeroOsdDisplayPortInit(void); +void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 3021608773..c13d3da510 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -169,6 +169,8 @@ static escSensorData_t *escDataCombined; #define AH_SIDEBAR_WIDTH_POS 7 #define AH_SIDEBAR_HEIGHT_POS 3 +static uint8_t leftScreen; + static const char compassBar[] = { SYM_HEADING_W, SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE, @@ -220,7 +222,7 @@ static const uint8_t osdElementDisplayOrder[] = { OSD_COMPASS_BAR }; -PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 4); +PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 5); /** * Gets the correct altitude symbol for the current unit system @@ -1155,7 +1157,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse) { if (!osdDisplayPortToUse) { return; } - BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31, 31)); + BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63, 31)); osdDisplayPort = osdDisplayPortToUse; #ifdef USE_CMS cmsDisplayPortRegister(osdDisplayPort); @@ -1163,19 +1165,25 @@ void osdInit(displayPort_t *osdDisplayPortToUse) { armState = ARMING_FLAG(ARMED); memset(blinkBits, 0, sizeof(blinkBits)); displayClearScreen(osdDisplayPort); - osdDrawLogo(3, 1); +#if defined(USE_HDZERO_OSD) + if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30)) + { leftScreen = HDINDENT; } + else +#endif + { leftScreen = SDINDENT; } + osdDrawLogo(leftScreen + 3, 1); char string_buffer[30]; tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, 20, 6, string_buffer); + displayWrite(osdDisplayPort, leftScreen + 20, 6, string_buffer); #ifdef USE_CMS - displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1); - displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2); - displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3); + displayWrite(osdDisplayPort, leftScreen + 7, 8, CMS_STARTUP_HELP_TEXT1); + displayWrite(osdDisplayPort, leftScreen + 11, 9, CMS_STARTUP_HELP_TEXT2); + displayWrite(osdDisplayPort, leftScreen + 11, 10, CMS_STARTUP_HELP_TEXT3); #endif #ifdef USE_RTC_TIME char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE]; if (osdFormatRtcDateTime(&dateTimeBuffer[0])) { - displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer); + displayWrite(osdDisplayPort, leftScreen + 5, 12, dateTimeBuffer); } #endif displayResync(osdDisplayPort); @@ -1376,9 +1384,9 @@ static void osdGetBlackboxStatusString(char * buff) { #endif static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char * value) { - displayWrite(osdDisplayPort, 2, y, text); - displayWrite(osdDisplayPort, 20, y, ":"); - displayWrite(osdDisplayPort, 22, y, value); + displayWrite(osdDisplayPort, leftScreen + 2, y, text); + displayWrite(osdDisplayPort, leftScreen + 20, y, ":"); + displayWrite(osdDisplayPort, leftScreen + 22, y, value); } /* @@ -1400,7 +1408,7 @@ static void osdShowStats(uint16_t endBatteryVoltage) { uint8_t top = 2; char buff[OSD_ELEMENT_BUFFER_LENGTH]; displayClearScreen(osdDisplayPort); - displayWrite(osdDisplayPort, 2, top++, " --- STATS ---"); + displayWrite(osdDisplayPort, leftScreen + 2, top++, " --- STATS ---"); if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) { bool success = false; #ifdef USE_RTC_TIME @@ -1409,7 +1417,7 @@ static void osdShowStats(uint16_t endBatteryVoltage) { if (!success) { tfp_sprintf(buff, "NO RTC"); } - displayWrite(osdDisplayPort, 2, top++, buff); + displayWrite(osdDisplayPort, leftScreen + 2, top++, buff); } if (osdStatGetState(OSD_STAT_TIMER_1)) { osdFormatTimer(buff, false, (OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1]) == OSD_TIMER_SRC_ON ? false : true), OSD_TIMER_1); @@ -1483,12 +1491,12 @@ static timeDelta_t osdShowArmed(void) timeDelta_t ret; displayClearScreen(osdDisplayPort); if ((osdConfig()->logo_on_arming == OSD_LOGO_ARMING_ON) || ((osdConfig()->logo_on_arming == OSD_LOGO_ARMING_FIRST) && !everArmed)) { - osdDrawLogo(3, 1); + osdDrawLogo(leftScreen + 3, 1); ret = osdConfig()->logo_on_arming_duration * 1e5; } else { ret = (REFRESH_1S / 2); } - displayWrite(osdDisplayPort, 12, 7, "ARMED"); + displayWrite(osdDisplayPort, leftScreen + 12, 7, "ARMED"); everArmed = true; return ret; } diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 824506ce82..15ffb20cc6 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -22,6 +22,7 @@ #include "common/time.h" #include "pg/pg.h" +#include "pg/vcd.h" #define OSD_NUM_TIMER_TYPES 3 extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES]; @@ -30,16 +31,23 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES]; #define VISIBLE_FLAG 0x0800 #define VISIBLE(x) (x & VISIBLE_FLAG) -#define OSD_POS_MAX 0x3FF -#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x3FF) // For CLI values + +#define OSD_POS_MAX 0x7FF +#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x7FF) // For CLI values // Character coordinate -#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31 -#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1) -#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS)) -#define OSD_X(x) (x & OSD_POSITION_XY_MASK) +#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31 +#define OSD_POSITION_BIT_XHD 10 // extra bit used to extend X range in a backward compatible manner for HD displays +#define OSD_POSITION_XHD_MASK (1 << OSD_POSITION_BIT_XHD) +#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1) +#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((x << (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)) & OSD_POSITION_XHD_MASK) | \ + ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS)) +#define OSD_X(x) ((x & OSD_POSITION_XY_MASK) | ((x & OSD_POSITION_XHD_MASK) >> (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS))) #define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK) +#define SDINDENT 0 //Analog leftmost character for OSD Init and Menus +#define HDINDENT 10 //HD leftmost character for OSD Init and Menus + // Timer configuration // Stored as 15[alarm:8][precision:4][source:4]0 #define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8)) diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 1d130f2fe2..da16313d93 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -214,11 +214,11 @@ portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialP return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED; } -bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction) { +bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction) { return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask); } -serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction) { +serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction) { for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) { const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i]; if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) { diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 071cdf45b6..fa4eeebc8a 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -50,6 +50,7 @@ typedef enum { FUNCTION_VTX_TRAMP = (1 << 13), // 8192 FUNCTION_RCDEVICE = (1 << 14), // 16384 FUNCTION_LIDAR_TF = (1 << 15), // 32768 + FUNCTION_HDZERO_OSD = (1 << 16) // 65536 } serialPortFunction_e; #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK) @@ -107,13 +108,13 @@ typedef struct serialPortUsage_s { serialPortIdentifier_e identifier; } serialPortUsage_t; -serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction); +serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction); // // configuration // typedef struct serialPortConfig_s { - uint16_t functionMask; + uint32_t functionMask; serialPortIdentifier_e identifier; uint8_t msp_baudrateIndex; uint8_t gps_baudrateIndex; @@ -145,7 +146,7 @@ serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function); serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function); portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function); -bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction); +bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction); void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier); diff --git a/src/main/io/spektrum_vtx_control.c b/src/main/io/spektrum_vtx_control.c index 61161a30e8..d591359078 100644 --- a/src/main/io/spektrum_vtx_control.c +++ b/src/main/io/spektrum_vtx_control.c @@ -113,6 +113,9 @@ const uint8_t vtxBsPi[SPEKTRUM_VTX_POWER_COUNT] = { #endif // USE_VTX_BEESIGN uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower) { +#if !(defined(USE_VTX_RTC6705) || defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)) + UNUSED(sPower); +#endif uint8_t devicePower = 0; const vtxDevice_t *vtxDevice = vtxCommonDevice(); switch (vtxCommonGetDeviceType(vtxDevice)) { diff --git a/src/main/msc/usbd_msc_desc.c b/src/main/msc/usbd_msc_desc.c index 2ebe7622fc..061c14563b 100644 --- a/src/main/msc/usbd_msc_desc.c +++ b/src/main/msc/usbd_msc_desc.c @@ -67,8 +67,10 @@ #define USBD_MANUFACTURER_STRING "STMicroelectronics" #define USBD_PRODUCT_HS_STRING "Mass Storage in HS Mode" #define USBD_PRODUCT_FS_STRING "Mass Storage in FS Mode" -#define USBD_CONFIGURATION_HS_STRING "MSC Config" -#define USBD_INTERFACE_HS_STRING "MSC Interface" +#define USBD_CONFIGURATION_HS_STRING "MSC Config in HS Mode" +#define USBD_INTERFACE_HS_STRING "MSC Interface in HS Mode" +#define USBD_CONFIGURATION_FS_STRING "MSC Config in FS Mode" +#define USBD_INTERFACE_FS_STRING "MSC Interface in FS Mode" /** * @} */ diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c index 9a32ffc400..4cc7b40f70 100644 --- a/src/main/msp/msp_serial.c +++ b/src/main/msp/msp_serial.c @@ -41,10 +41,9 @@ static mspPort_t mspPorts[MAX_MSP_PORT_COUNT]; -static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, bool sharedWithTelemetry) { +void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort) { memset(mspPortToReset, 0, sizeof(mspPort_t)); mspPortToReset->port = serialPort; - mspPortToReset->sharedWithTelemetry = sharedWithTelemetry; } void mspSerialAllocatePorts(void) { @@ -58,8 +57,8 @@ void mspSerialAllocatePorts(void) { } serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); if (serialPort) { - bool sharedWithTelemetry = isSerialPortShared(portConfig, FUNCTION_MSP, TELEMETRY_PORT_FUNCTIONS_MASK); - resetMspPort(mspPort, serialPort, sharedWithTelemetry); + resetMspPort(mspPort, serialPort); + mspPort->sharedWithTelemetry = isSerialPortShared(portConfig, FUNCTION_MSP, TELEMETRY_PORT_FUNCTIONS_MASK); portIndex++; } portConfig = findNextSerialPortConfig(FUNCTION_MSP); @@ -505,3 +504,54 @@ uint32_t mspSerialTxBytesFree(void) { } return ret; } + +int mspSerialPushPort(uint16_t cmd, const uint8_t *data, int datalen, mspPort_t *mspPort, mspVersion_e version) +{ + uint8_t pushBuf[MSP_PORT_OUTBUF_SIZE]; + + mspPacket_t push = { + .buf = { .ptr = pushBuf, .end = ARRAYEND(pushBuf), }, + .cmd = cmd, + .result = 0, + }; + + sbufWriteData(&push.buf, data, datalen); + + sbufSwitchToReader(&push.buf, pushBuf); + + return mspSerialEncode(mspPort, &push, version); +} + +void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn) +{ + mspPostProcessFnPtr mspPostProcessFn = NULL; + + if (serialRxBytesWaiting(mspPort->port)) { + // There are bytes incoming - abort pending request + mspPort->lastActivityMs = millis(); + mspPort->pendingRequest = MSP_PENDING_NONE; + + // Process incoming bytes + while (serialRxBytesWaiting(mspPort->port)) { + const uint8_t c = serialRead(mspPort->port); + const bool consumed = mspSerialProcessReceivedData(mspPort, c); + + if (!consumed && evaluateNonMspData == MSP_EVALUATE_NON_MSP_DATA) { + mspEvaluateNonMspData(mspPort, c); + } + + if (mspPort->c_state == MSP_COMMAND_RECEIVED) { + mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn); + break; // process one command at a time so as not to block. + } + } + + if (mspPostProcessFn) { + waitForSerialPortToFinishTransmitting(mspPort->port); + mspPostProcessFn(mspPort->port); + } + } + else { + mspProcessPendingRequest(mspPort); + } +} \ No newline at end of file diff --git a/src/main/msp/msp_serial.h b/src/main/msp/msp_serial.h index b1718323a0..cac9ca8723 100644 --- a/src/main/msp/msp_serial.h +++ b/src/main/msp/msp_serial.h @@ -22,6 +22,7 @@ #include "drivers/time.h" #include "interface/msp.h" +#include "io/serial.h" // Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports. #define MAX_MSP_PORT_COUNT 3 @@ -122,3 +123,6 @@ void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort); void mspSerialReleaseSharedTelemetryPorts(void); int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction); uint32_t mspSerialTxBytesFree(void); +int mspSerialPushPort(uint16_t cmd, const uint8_t *data, int datalen, mspPort_t *mspPort, mspVersion_e version); +void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort); +void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn); \ No newline at end of file diff --git a/src/main/pg/board.c b/src/main/pg/board.c index a3d17831ea..28f692c867 100644 --- a/src/main/pg/board.c +++ b/src/main/pg/board.c @@ -37,14 +37,14 @@ PG_REGISTER_WITH_RESET_FN(boardConfig_t, boardConfig, PG_BOARD_CONFIG, 0); void pgResetFn_boardConfig(boardConfig_t *boardConfig) { if (boardInformationIsSet()) { - strncpy(boardConfig->manufacturerId, getManufacturerId(), MAX_MANUFACTURER_ID_LENGTH); - strncpy(boardConfig->boardName, getBoardName(), MAX_BOARD_NAME_LENGTH); + strncpy(boardConfig->manufacturerId, getManufacturerId(), MAX_MANUFACTURER_ID_LENGTH + 1); + strncpy(boardConfig->boardName, getBoardName(), MAX_BOARD_NAME_LENGTH + 1); boardConfig->boardInformationSet = true; } else { #if !defined(GENERIC_TARGET) - strncpy(boardConfig->boardName, targetName, MAX_BOARD_NAME_LENGTH); + strncpy(boardConfig->boardName, targetName, MAX_BOARD_NAME_LENGTH + 1); #if defined(TARGET_MANUFACTURER_IDENTIFIER) - strncpy(boardConfig->manufacturerId, TARGET_MANUFACTURER_IDENTIFIER, MAX_MANUFACTURER_ID_LENGTH); + strncpy(boardConfig->manufacturerId, TARGET_MANUFACTURER_IDENTIFIER, MAX_MANUFACTURER_ID_LENGTH + 1); #endif boardConfig->boardInformationSet = true; #else diff --git a/src/main/pg/bus_spi.c b/src/main/pg/bus_spi.c index a51b0e9378..e8e50fc84f 100644 --- a/src/main/pg/bus_spi.c +++ b/src/main/pg/bus_spi.c @@ -91,9 +91,18 @@ 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 +#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/pg/vcd.h b/src/main/pg/vcd.h index df3ed8001d..33ff77155a 100644 --- a/src/main/pg/vcd.h +++ b/src/main/pg/vcd.h @@ -27,7 +27,8 @@ enum VIDEO_SYSTEMS { VIDEO_SYSTEM_AUTO = 0, VIDEO_SYSTEM_PAL, - VIDEO_SYSTEM_NTSC + VIDEO_SYSTEM_NTSC, + VIDEO_SYSTEM_HD }; typedef struct vcdProfile_s { diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 649712c084..f9dedb68ba 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -130,6 +130,7 @@ typedef struct crsfPayloadLinkstatistics_s { } crsfLinkStatistics_t; static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, timeUs_t currentTimeUs) { + UNUSED(currentTimeUs); const crsfLinkStatistics_t stats = *statsPtr; CRSFsetLQ(stats.uplink_Link_quality); CRSFsetRFMode(stats.rf_Mode); diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 1d1f08b132..6a45d357b4 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -43,8 +43,10 @@ #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" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -298,6 +300,42 @@ 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: + 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..5b132c53f6 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -47,7 +47,10 @@ typedef enum { ACC_ICM20608G, ACC_ICM20649, ACC_ICM20689, + 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 60d6a62df3..37bf1856cf 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -44,8 +44,10 @@ #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" #include "drivers/accgyro/accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h" @@ -157,8 +159,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; @@ -208,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_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 @@ -249,6 +253,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .checkOverflow = GYRO_OVERFLOW_CHECK_ALL_AXES, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, + .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, @@ -304,6 +309,7 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_offset_yaw = 0, .yaw_spin_recovery = YAW_SPIN_RECOVERY_AUTO, .yaw_spin_threshold = 1950, + .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, @@ -496,6 +502,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)) { @@ -507,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)) { @@ -536,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_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 @@ -581,9 +623,12 @@ 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: + case GYRO_ICM42688P: + case GYRO_ICM42605: gyroSensor->gyroDev.gyroHasOverflowProtection = true; break; case GYRO_ICM20601: @@ -717,6 +762,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; @@ -724,6 +770,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; } @@ -817,7 +864,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); } @@ -862,11 +909,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 1bbb627a89..671d7b7cbd 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -53,7 +53,10 @@ typedef enum { GYRO_ICM20608G, GYRO_ICM20649, GYRO_ICM20689, + GYRO_ICM42605, + GYRO_ICM42688P, GYRO_BMI160, + GYRO_BMI270, GYRO_IMUF9001, GYRO_FAKE } gyroSensor_e; @@ -111,6 +114,11 @@ typedef struct smithPredictor_s { } smithPredictor_t; #endif // USE_SMITH_PREDICTOR +typedef enum { + RP = 0, + RPY = 1 +} dynamicGyroAxisType_e; + 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. @@ -144,6 +152,7 @@ typedef struct gyroConfig_s { int16_t yaw_spin_threshold; uint16_t gyroCalibrationDuration; // Gyro calibration duration in 1/100 second + uint8_t dyn_notch_axis; uint16_t dyn_notch_q; uint8_t dyn_notch_count; uint16_t dyn_notch_min_hz; @@ -196,7 +205,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 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/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h index d5b04e3b1e..063672ca1e 100644 --- a/src/main/target/ALIENWHOOP/target.h +++ b/src/main/target/ALIENWHOOP/target.h @@ -38,12 +38,17 @@ /* Multi-Arch Support for 168MHz or 216MHz ARM Cortex processors - STM32F405RGT or STM32F7RET */ + +#define TARGET_MANUFACTURER_IDENTIFIER "ALWH" + #if defined(ALIENWHOOPF4) -#define TARGET_BOARD_IDENTIFIER "AWF4" -#define USBD_PRODUCT_STRING "AlienWhoopF4" +#define USBD_PRODUCT_STRING "ALIENWHOOPF4" +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #else -#define TARGET_BOARD_IDENTIFIER "AWF7" -#define USBD_PRODUCT_STRING "AlienWhoopF7" +#define USBD_PRODUCT_STRING "ALIENWHOOPF7" +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" #endif #define USE_TARGET_CONFIG // see config.c for target specific customizations @@ -125,6 +130,9 @@ // MPU #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_INSTANCE SPI1 +#define MPU9250_CS_PIN SPI1_NSS_PIN +#define MPU9250_SPI_INSTANCE SPI1 + #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW // MAG @@ -136,11 +144,15 @@ // GYRO #define USE_GYRO #define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU9250 #define GYRO_MPU6500_ALIGN CW0_DEG +#define GYRO_MPU9250_ALIGN CW0_DEG // ACC #define USE_ACC #define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU9250 #define ACC_MPU6500_ALIGN CW0_DEG +#define ACC_MPU9250_ALIGN CW0_DEG /* Optional Digital Pressure Sensor (barometer) - Bosch BMP280 * TODO: not implemented on V1 or V2 pcb @@ -232,6 +244,10 @@ #define TARGET_IO_PORTE 0xffff #endif +#define USE_ADC +#define ADC1_DMA_OPT 1 +#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0 + /* Timers */ #define USABLE_TIMER_CHANNEL_COUNT 5 diff --git a/src/main/target/ALIENWHOOP/target.mk b/src/main/target/ALIENWHOOP/target.mk index 4d72357939..73c66b293b 100644 --- a/src/main/target/ALIENWHOOP/target.mk +++ b/src/main/target/ALIENWHOOP/target.mk @@ -20,6 +20,7 @@ FEATURES += ONBOARDFLASH VCP TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu9250.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_ak8963.c \ drivers/flash_m25p16.c \ diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h index c3508959a8..2c46a633a5 100644 --- a/src/main/target/BETAFLIGHTF4/target.h +++ b/src/main/target/BETAFLIGHTF4/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "BFF4" -#define USBD_PRODUCT_STRING "BetaFlightF4" +#define TARGET_MANUFACTURER_IDENTIFIER "FPVM" +#define USBD_PRODUCT_STRING "BETAFLIGHTF4" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #define LED0_PIN PB5 @@ -32,18 +35,24 @@ // PC13 used as inverter select GPIO for UART2 #define INVERTER_PIN_UART2 PC13 -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 - #define USE_ACC #define USE_ACC_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG #define USE_GYRO #define USE_GYRO_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 // MPU6000 interrupts #define USE_EXTI @@ -122,6 +131,9 @@ #define I2C2_SCL NONE // PB10, UART3_TX #define I2C2_SDA NONE // PB11, UART3_RX #define I2C_DEVICE (I2CDEV_2) +#define MAG_I2C_INSTANCE (I2CDEV_2) +#define BARO_I2C_INSTANCE (I2CDEV_2) +#define DASHBOARD_I2C_INSTANCE (I2CDEV_2) #define USE_ADC #define CURRENT_METER_ADC_PIN PC1 @@ -133,7 +145,7 @@ #define SBUS_TELEMETRY_UART SERIAL_PORT_USART2 #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define DEFAULT_FEATURES ( FEATURE_TELEMETRY | FEATURE_OSD ) +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) #define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) #define TARGET_IO_PORTB (0xffff & ~(BIT(2))) diff --git a/src/main/target/BETAFLIGHTF4/target.mk b/src/main/target/BETAFLIGHTF4/target.mk index ca33021603..cd44e934c4 100644 --- a/src/main/target/BETAFLIGHTF4/target.mk +++ b/src/main/target/BETAFLIGHTF4/target.mk @@ -5,6 +5,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_bmp280.c \ drivers/barometer/barometer_ms5611.c \ drivers/compass/compass_hmc5883l.c \ 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 \ diff --git a/src/main/target/BETAFPVF411RX/target.h b/src/main/target/BETAFPVF411RX/target.h index b4cbe47a34..2a68447eda 100644 --- a/src/main/target/BETAFPVF411RX/target.h +++ b/src/main/target/BETAFPVF411RX/target.h @@ -38,27 +38,35 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define MPU6000_CS_PIN PA4 -//#define ICM20689_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 -//#define ICM20689_SPI_INSTANCE SPI1 - #define USE_EXTI #define USE_GYRO_EXTI #define MPU_INT_EXTI PB6 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW0_DEG_FLIP -//#define USE_GYRO_SPI_ICM20689 -//#define ACC_ICM20689_ALIGN CW180_DEG #define USE_ACC +#define USE_GYRO + #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW0_DEG_FLIP -//#define USE_ACC_SPI_ICM20689 -//#define ACC_ICM20689_ALIGN CW180_DEG +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USE_ACCGYRO_BMI270 +#define USE_SPI_GYRO +#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 @@ -140,17 +148,17 @@ #define MAX7456_SPI_INSTANCE SPI2 #define MAX7456_SPI_CS_PIN PB12 -//#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -//#define USE_FLASHFS -//#define USE_FLASH_M25P16 -//#define FLASH_CS_PIN PB2 -//#define FLASH_SPI_INSTANCE SPI2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define FLASH_CS_PIN PB2 +#define FLASH_SPI_INSTANCE SPI2 // *************** ADC ***************************** #define USE_ADC #define ADC_INSTANCE ADC1 -#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0 - +//#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0 +#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0 #define VBAT_ADC_PIN PA1 #define CURRENT_METER_ADC_PIN PB0 //#define RSSI_ADC_PIN PB1 @@ -166,7 +174,7 @@ //#define PINIO2_PIN PA15 // Camera switcher //#define USE_PINIOBOX -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_SOFTSERIAL) #define CURRENT_METER_SCALE_DEFAULT 179 #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC diff --git a/src/main/target/BETAFPVF411RX/target.mk b/src/main/target/BETAFPVF411RX/target.mk index 965b78488e..e9ecda64c7 100644 --- a/src/main/target/BETAFPVF411RX/target.mk +++ b/src/main/target/BETAFPVF411RX/target.mk @@ -1,18 +1,19 @@ F411_TARGETS += $(TARGET) - -FEATURES += VCP +FEATURES += VCP ONBOARDFLASH TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_icm20689.c \ + 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_bmi270.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 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 \ diff --git a/src/main/target/CRASHTESTF7/TALONF7V2.md b/src/main/target/CRASHTESTF7/TALONF7V2.md deleted file mode 100644 index 8624f95d55..0000000000 --- a/src/main/target/CRASHTESTF7/TALONF7V2.md +++ /dev/null @@ -1,12 +0,0 @@ -MCU: STM32F722RE -IMU: ICM-20602 -IMU Interrupt: yes -BARO: NO -VCP: YES -Hardware UARTS: 6 uarts -OSD: uses a AB7456 chip -Blackbox: flash Chip -PPM/UART NOT Shared: YES -Battery Voltage Sensor: 10:1 -Current sensor: from 4 in 1 socket -Integrated Voltage Regulator: 1.5A 5v/v1 2A 5v/v2 diff --git a/src/main/target/CRASHTESTF7/target.h b/src/main/target/CRASHTESTF7/target.h deleted file mode 100644 index 859462f588..0000000000 --- a/src/main/target/CRASHTESTF7/target.h +++ /dev/null @@ -1,153 +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 TARGET_BOARD_IDENTIFIER "S7X2" //not sure if this even shows, but defaults on BF as STM used -#define USBD_PRODUCT_STRING "BotF7" //board name on configurator drop down menu, flasher tab -#define TARGET_MANUFACTURER_IDENTIFIER "BQEio" //Manufacturer abbreviation - -#define USE_TARGET_CONFIG - -#define ENABLE_DSHOT_DMAR true //Dshot default - -//Aux -#define LED0_PIN PB0 //resource led 1 - -#define USE_BEEPER -#define BEEPER_PIN PB4 //resource beeper 1 -#define BEEPER_INVERTED //set beeper_inversion = on - -#define USE_PINIO -#define PINIO1_PIN PA14 // VTX power switcher -#define USE_PINIOBOX - - -//define camera control -#define CAMERA_CONTROL_PIN PB3 // resource camera_control 1 - -//MPU-6000 -#define USE_GYRO //declaring usage of gyro accelerometer and Spi access -#define USE_ACC -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6000 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - -#define MPU_INT_EXTI PC4 //gyro_1_exti_pin for mpu6000 -#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN -#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE -#define GYRO_MPU6000_ALIGN CW0_DEG //set gyro_1_align -#define ACC_MPU6000_ALIGN CW0_DEG //set accel_1_align (normally same as gyro 1) - -// OSD -#define USE_MAX7456 //osd driver -#define MAX7456_SPI_INSTANCE SPI3 // set max7456 -#define MAX7456_SPI_CS_PIN PA15 // resource osd_cs 1 -#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz -#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) - -// Blackbox -#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define USE_FLASHFS // enable flash blackbox -#define USE_FLASH_M25P16 //defines which driver type -#define FLASH_CS_PIN PB12 //resource flash_cs -#define FLASH_SPI_INSTANCE SPI2 //set flash spi bus - -// Uarts -#define USE_UART1 //enable corresponding UARTS -#define UART1_RX_PIN PA10 //resource serial_rx 1 -#define UART1_TX_PIN PA9 //resource serial_tx 1 - -#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_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -//#define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 7 //VCP, USART1, USART2,USART3,USART4,USART5,USART6 - -// ESC -#define USE_ADC // enable adc -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC //define source.. same as battery tab in configurator -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC -#define CURRENT_METER_ADC_PIN PC1 //resource adc_curr -#define VBAT_ADC_PIN PC2 //resource adc_batt -#define RSSI_ADC_PIN PC3 //resource adc_rssi -#define CURRENT_METER_SCALE_DEFAULT 150 // 3.3/120A = 25mv/A -#define VBAT_SCALE 160 //configurator tab voltage scale - - - - -// SPI devices -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 - -#define SPI1_NSS_PIN PA4 //resource usually matches cs pin of device that calls for it -#define SPI1_SCK_PIN PA5 // resource spi_sck 1 -#define SPI1_MISO_PIN PA6 //resource spi_miso 1 -#define SPI1_MOSI_PIN PA7 //resource spi_mosi - -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define SPI3_NSS_PIN PA15 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PB5 - -// USB -#define USE_VCP -#define BINDPLUG_PIN PB2 -#define SERIALRX_PROVIDER SERIALRX_CRSF -#define SERIALRX_UART SERIAL_PORT_USART3 - -//FEATURE -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE) -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL - -// IO Ports -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) - -// timers -#define USABLE_TIMER_CHANNEL_COUNT 9 //updated timer count to compensate for Nf Motor 4, total timers defined in target.c -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) //update based on update CLRACINGF7 Target BF4.1+ timers defined, enumerated as per use diff --git a/src/main/target/DAFP_DARWINF722HD/config.c b/src/main/target/DARWINF722HD/config.c similarity index 100% rename from src/main/target/DAFP_DARWINF722HD/config.c rename to src/main/target/DARWINF722HD/config.c diff --git a/src/main/target/DAFP_DARWINF722HD/target.c b/src/main/target/DARWINF722HD/target.c similarity index 100% rename from src/main/target/DAFP_DARWINF722HD/target.c rename to src/main/target/DARWINF722HD/target.c diff --git a/src/main/target/DAFP_DARWINF722HD/target.h b/src/main/target/DARWINF722HD/target.h similarity index 100% rename from src/main/target/DAFP_DARWINF722HD/target.h rename to src/main/target/DARWINF722HD/target.h diff --git a/src/main/target/DAFP_DARWINF722HD/target.mk b/src/main/target/DARWINF722HD/target.mk similarity index 100% rename from src/main/target/DAFP_DARWINF722HD/target.mk rename to src/main/target/DARWINF722HD/target.mk diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.c b/src/main/target/FLYWOOF411FR/target.c similarity index 100% rename from src/main/target/FLWO_FLYWOOF411FR/target.c rename to src/main/target/FLYWOOF411FR/target.c diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.h b/src/main/target/FLYWOOF411FR/target.h similarity index 99% rename from src/main/target/FLWO_FLYWOOF411FR/target.h rename to src/main/target/FLYWOOF411FR/target.h index 42724e2881..3e95bdc8cf 100644 --- a/src/main/target/FLWO_FLYWOOF411FR/target.h +++ b/src/main/target/FLYWOOF411FR/target.h @@ -169,5 +169,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USABLE_TIMER_CHANNEL_COUNT 10 #define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4) ) diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.mk b/src/main/target/FLYWOOF411FR/target.mk similarity index 100% rename from src/main/target/FLWO_FLYWOOF411FR/target.mk rename to src/main/target/FLYWOOF411FR/target.mk diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.c b/src/main/target/FLYWOOF411V2/target.c similarity index 100% rename from src/main/target/FLWO_FLYWOOF411V2/target.c rename to src/main/target/FLYWOOF411V2/target.c diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.h b/src/main/target/FLYWOOF411V2/target.h similarity index 100% rename from src/main/target/FLWO_FLYWOOF411V2/target.h rename to src/main/target/FLYWOOF411V2/target.h diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.mk b/src/main/target/FLYWOOF411V2/target.mk similarity index 100% rename from src/main/target/FLWO_FLYWOOF411V2/target.mk rename to src/main/target/FLYWOOF411V2/target.mk diff --git a/src/main/target/FLYWOOF411_5IN1_AIO/target.h b/src/main/target/FLYWOOF411_5IN1_AIO/target.h index c3cf698af1..33c06dde11 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.h +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.h @@ -61,6 +61,20 @@ //#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 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 d6dc58877c..a0f0b8aff2 100644 --- a/src/main/target/FLYWOOF411_5IN1_AIO/target.mk +++ b/src/main/target/FLYWOOF411_5IN1_AIO/target.mk @@ -3,21 +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/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 diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c new file mode 100644 index 0000000000..a0255f4f3a --- /dev/null +++ b/src/main/target/FOXEERF722V4/target.c @@ -0,0 +1,44 @@ +/* + * 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: bc7d9ef + +#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_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // ppm + DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check + DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h new file mode 100644 index 0000000000..47c8a127e7 --- /dev/null +++ b/src/main/target/FOXEERF722V4/target.h @@ -0,0 +1,155 @@ +/* + * 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: bc7d9ef + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "FOXE" +#define USBD_PRODUCT_STRING "FOXEERF722V4" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_ADC +#define USE_SPI_GYRO +#define USE_BARO + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 //works in place of W25Q128FV +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC15 +#define LED_STRIP_PIN PA15 +#define USE_BEEPER +#define BEEPER_PIN PA4 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PB3 + +#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 GYRO_1_ALIGN CW270_DEG +#define ACC_1_ALIGN CW270_DEG +#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_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_MPU_DATA_READY_SIGNAL + +#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC_ICM42688P_ALIGN CW270_DEG +#define GYRO_ICM42688P_ALIGN CW270_DEG +#define ICM42688P_CS_PIN PB2 +#define ICM42688P_SPI_INSTANCE SPI1 + +#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 RX_PPM_PIN PB7 +#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 FLASH_CS_PIN PB12 +#define FLASH_SPI_INSTANCE SPI2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define MAX7456_SPI_CS_PIN PC3 +#define MAX7456_SPI_INSTANCE SPI3 + +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PA0 +#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 ADC_INSTANCE ADC3 + +#define ENABLE_DSHOT_DMAR true + +#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 + +#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(8) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk new file mode 100644 index 0000000000..4cac437e26 --- /dev/null +++ b/src/main/target/FOXEERF722V4/target.mk @@ -0,0 +1,16 @@ +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/light_led.h \ +drivers/light_ws2811strip.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: bc7d9ef diff --git a/src/main/target/FOXEERF745V3_AIO/target.c b/src/main/target/FOXEERF745V3_AIO/target.c new file mode 100644 index 0000000000..4e8a894d52 --- /dev/null +++ b/src/main/target/FOXEERF745V3_AIO/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 . + */ + +// This resource file generated using https://github.com/nerdCopter/target-convert +// Commit: 40b5552 + +#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_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/FOXEERF745V3_AIO/target.h b/src/main/target/FOXEERF745V3_AIO/target.h new file mode 100644 index 0000000000..fd00e29fc2 --- /dev/null +++ b/src/main/target/FOXEERF745V3_AIO/target.h @@ -0,0 +1,138 @@ +/* + * 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: 40b5552 + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "FOXE" +#define USBD_PRODUCT_STRING "FOXEERF745V3_AIO" + +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC13 +#define LED_STRIP_PIN PA8 +#define USE_BEEPER +#define BEEPER_PIN PD2 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PB3 + +#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 USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define GYRO_1_ALIGN CW90_DEG +#define ACC_1_ALIGN CW90_DEG +#define GYRO_1_CS_PIN PA15 +#define GYRO_1_EXTI_PIN PD0 +#define GYRO_1_SPI_INSTANCE SPI3 +#define MPU_INT_EXTI PD0 + +#define ACC_ICM42688P_ALIGN CW90_DEG +#define GYRO_ICM42688P_ALIGN CW90_DEG +#define ICM42688P_CS_PIN PA15 +#define ICM42688P_SPI_INSTANCE SPI3 + +#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_TX_PIN PA0 +#define UART4_RX_PIN PA1 +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 +#define SERIAL_PORT_COUNT 6 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C_DEVICE (I2CDEV_1) +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define FLASH_CS_PIN PE4 +#define FLASH_SPI_INSTANCE SPI4 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define MAX7456_SPI_CS_PIN PA4 +#define MAX7456_SPI_INSTANCE SPI1 + +#define USE_ADC +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PC5 +#define ADC1_DMA_OPT 0 +#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 100 + +#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 +// 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 + +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/FOXEERF745V3_AIO/target.mk b/src/main/target/FOXEERF745V3_AIO/target.mk new file mode 100644 index 0000000000..6c6e3df109 --- /dev/null +++ b/src/main/target/FOXEERF745V3_AIO/target.mk @@ -0,0 +1,12 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_icm426xx.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/max7456.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 40b5552 diff --git a/src/main/target/DIAT_MAMBAF405US/DIAT_MAMBAF405US_I2C.mk b/src/main/target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk similarity index 100% rename from src/main/target/DIAT_MAMBAF405US/DIAT_MAMBAF405US_I2C.mk rename to src/main/target/FOXEERF745_AIO/FOXEERF745_AIO_V2.mk 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 diff --git a/src/main/target/TURC_FPVCYCLEF401/target.c b/src/main/target/FPVCYCLEF401/target.c similarity index 100% rename from src/main/target/TURC_FPVCYCLEF401/target.c rename to src/main/target/FPVCYCLEF401/target.c diff --git a/src/main/target/TURC_FPVCYCLEF401/target.h b/src/main/target/FPVCYCLEF401/target.h similarity index 100% rename from src/main/target/TURC_FPVCYCLEF401/target.h rename to src/main/target/FPVCYCLEF401/target.h diff --git a/src/main/target/TURC_FPVCYCLEF401/target.mk b/src/main/target/FPVCYCLEF401/target.mk similarity index 100% rename from src/main/target/TURC_FPVCYCLEF401/target.mk rename to src/main/target/FPVCYCLEF401/target.mk 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 diff --git a/src/main/target/CRASHTESTF7/target.c b/src/main/target/GEPRC_F722_AIO/target.c similarity index 50% rename from src/main/target/CRASHTESTF7/target.c rename to src/main/target/GEPRC_F722_AIO/target.c index c2489acc41..5fdda10d02 100644 --- a/src/main/target/CRASHTESTF7/target.c +++ b/src/main/target/GEPRC_F722_AIO/target.c @@ -17,6 +17,7 @@ * * If not, see . */ + #include #include "platform.h" @@ -27,18 +28,18 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { -// FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION - DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL - - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // D2-ST2/D2-ST4 MOTOR4 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST4 MOTOR5 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // D2-ST7 MOTOR7 +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(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5 +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 diff --git a/src/main/target/HENA_TALONF7DJIHD/target.mk b/src/main/target/HENA_TALONF7DJIHD/target.mk deleted file mode 100644 index 8626fa065d..0000000000 --- a/src/main/target/HENA_TALONF7DJIHD/target.mk +++ /dev/null @@ -1,8 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/max7456.c diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.c b/src/main/target/HOBBYWING_XROTORF7CONV/target.c similarity index 100% rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.c rename to src/main/target/HOBBYWING_XROTORF7CONV/target.c diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.h b/src/main/target/HOBBYWING_XROTORF7CONV/target.h similarity index 100% rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.h rename to src/main/target/HOBBYWING_XROTORF7CONV/target.h diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.mk b/src/main/target/HOBBYWING_XROTORF7CONV/target.mk similarity index 100% rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.mk rename to src/main/target/HOBBYWING_XROTORF7CONV/target.mk diff --git a/src/main/target/IFLIGHT_BLITZ_F405/target.h b/src/main/target/IFLIGHT_BLITZ_F405/target.h index 45e86da05b..bb0d69a611 100644 --- a/src/main/target/IFLIGHT_BLITZ_F405/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F405/target.h @@ -21,9 +21,11 @@ //#define USE_TARGET_CONFIG -#define TARGET_BOARD_IDENTIFIER "IBF4" -#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" -#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F405" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F405" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #define LED0_PIN PC15 diff --git a/src/main/target/IFF4_TWIN_G/IFF4_TWIN_G_M.mk b/src/main/target/IFLIGHT_F405_TWING/IFLIGHT_F405_TWING_M.mk.bak similarity index 100% rename from src/main/target/IFF4_TWIN_G/IFF4_TWIN_G_M.mk rename to src/main/target/IFLIGHT_F405_TWING/IFLIGHT_F405_TWING_M.mk.bak diff --git a/src/main/target/IFF4_AIO/target.c b/src/main/target/IFLIGHT_F405_TWING/target.c similarity index 100% rename from src/main/target/IFF4_AIO/target.c rename to src/main/target/IFLIGHT_F405_TWING/target.c diff --git a/src/main/target/IFF4_TWIN_G/target.h b/src/main/target/IFLIGHT_F405_TWING/target.h similarity index 96% rename from src/main/target/IFF4_TWIN_G/target.h rename to src/main/target/IFLIGHT_F405_TWING/target.h index 9253ffe9e7..c8a693f7c9 100644 --- a/src/main/target/IFF4_TWIN_G/target.h +++ b/src/main/target/IFLIGHT_F405_TWING/target.h @@ -20,12 +20,12 @@ #pragma once -#if defined(IFF4_TWIN_G_M) +#if defined(IFLIGHT_F405_TWING_M) #define TARGET_BOARD_IDENTIFIER "S405" -#define USBD_PRODUCT_STRING "IFLIGHTF4TWIN_G_mpu6000" +#define USBD_PRODUCT_STRING "IFLIGHT_F405_TWING_M" #else #define TARGET_BOARD_IDENTIFIER "S405" -#define USBD_PRODUCT_STRING "IFLIGHTF4TWIN_G" +#define USBD_PRODUCT_STRING "IFLIGHT_F405_TWING" #endif #define USE_DSHOT_DMAR @@ -47,7 +47,7 @@ #define PINIO1_PIN PC14 #define PINIO2_PIN PC15 -#if defined(IFF4_TWIN_G_M) +#if defined(IFLIGHT_F405_TWING_M) #define USE_MPU_DATA_READY_SIGNAL #define USE_EXTI diff --git a/src/main/target/IFF4_TWIN_G/target.mk b/src/main/target/IFLIGHT_F405_TWING/target.mk similarity index 100% rename from src/main/target/IFF4_TWIN_G/target.mk rename to src/main/target/IFLIGHT_F405_TWING/target.mk diff --git a/src/main/target/IFF4_TWIN_G/target.c b/src/main/target/IFLIGHT_F411_AIO32/target.c similarity index 100% rename from src/main/target/IFF4_TWIN_G/target.c rename to src/main/target/IFLIGHT_F411_AIO32/target.c diff --git a/src/main/target/IFF4_AIO/target.h b/src/main/target/IFLIGHT_F411_AIO32/target.h similarity index 94% rename from src/main/target/IFF4_AIO/target.h rename to src/main/target/IFLIGHT_F411_AIO32/target.h index 0851f4f9e4..057462579d 100644 --- a/src/main/target/IFF4_AIO/target.h +++ b/src/main/target/IFLIGHT_F411_AIO32/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "S411" -#define USBD_PRODUCT_STRING "IFLIGHT F411 AIO" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_F411_AIO32" + +#define FC_TARGET_MCU STM32F411 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S411" // generic ID #define LED0_PIN PB5 diff --git a/src/main/target/IFF4_AIO/target.mk b/src/main/target/IFLIGHT_F411_AIO32/target.mk similarity index 100% rename from src/main/target/IFF4_AIO/target.mk rename to src/main/target/IFLIGHT_F411_AIO32/target.mk diff --git a/src/main/target/IFF411_PRO/target.c b/src/main/target/IFLIGHT_F411_PRO/target.c similarity index 100% rename from src/main/target/IFF411_PRO/target.c rename to src/main/target/IFLIGHT_F411_PRO/target.c diff --git a/src/main/target/IFF411_PRO/target.h b/src/main/target/IFLIGHT_F411_PRO/target.h similarity index 96% rename from src/main/target/IFF411_PRO/target.h rename to src/main/target/IFLIGHT_F411_PRO/target.h index d84e8ed6f4..2539723608 100644 --- a/src/main/target/IFF411_PRO/target.h +++ b/src/main/target/IFLIGHT_F411_PRO/target.h @@ -19,8 +19,12 @@ */ #pragma once -#define TARGET_BOARD_IDENTIFIER "S411" -#define USBD_PRODUCT_STRING "IFLIGHT F411 PRO" + +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_F411_PRO" + +#define FC_TARGET_MCU STM32F411 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S411" // generic ID #define ENABLE_DSHOT_DMAR true diff --git a/src/main/target/IFF411_PRO/target.mk b/src/main/target/IFLIGHT_F411_PRO/target.mk similarity index 100% rename from src/main/target/IFF411_PRO/target.mk rename to src/main/target/IFLIGHT_F411_PRO/target.mk diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c b/src/main/target/IFLIGHT_F722_TWING/target.c similarity index 96% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c rename to src/main/target/IFLIGHT_F722_TWING/target.c index f6780a1a41..b8641b75c6 100644 --- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c +++ b/src/main/target/IFLIGHT_F722_TWING/target.c @@ -28,7 +28,7 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //cam DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM diff --git a/src/main/target/IFF7_TWIN_G/target.h b/src/main/target/IFLIGHT_F722_TWING/target.h similarity index 95% rename from src/main/target/IFF7_TWIN_G/target.h rename to src/main/target/IFLIGHT_F722_TWING/target.h index dcaf56de6f..535a4b68b0 100644 --- a/src/main/target/IFF7_TWIN_G/target.h +++ b/src/main/target/IFLIGHT_F722_TWING/target.h @@ -20,9 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "S7X2" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_F722_TWING" -#define USBD_PRODUCT_STRING "IFLIGHT F7 TWIN G" +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID #define USE_DUAL_GYRO diff --git a/src/main/target/IFF7_TWIN_G/target.mk b/src/main/target/IFLIGHT_F722_TWING/target.mk similarity index 100% rename from src/main/target/IFF7_TWIN_G/target.mk rename to src/main/target/IFLIGHT_F722_TWING/target.mk diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.c b/src/main/target/IFLIGHT_F745_AIO/target.c similarity index 100% rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.c rename to src/main/target/IFLIGHT_F745_AIO/target.c diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.h b/src/main/target/IFLIGHT_F745_AIO/target.h similarity index 96% rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.h rename to src/main/target/IFLIGHT_F745_AIO/target.h index 0cf4b6b8b7..c32ed746ed 100644 --- a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.h +++ b/src/main/target/IFLIGHT_F745_AIO/target.h @@ -20,10 +20,12 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "IFRC" - +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" #define USBD_PRODUCT_STRING "IFLIGHT_F745_AIO" +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + #define LED0_PIN PC13 #define USE_BEEPER diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.mk b/src/main/target/IFLIGHT_F745_AIO/target.mk similarity index 100% rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.mk rename to src/main/target/IFLIGHT_F745_AIO/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..e9a9e73836 --- /dev/null +++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.h @@ -0,0 +1,190 @@ +/* + * 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 "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_F745_AIO_V2" + +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + +#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..7cfd60c081 --- /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_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/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_hal.c \ + drivers/max7456.c diff --git a/src/main/target/IFF4_E/target.c b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.c similarity index 100% rename from src/main/target/IFF4_E/target.c rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.c diff --git a/src/main/target/IFF4_E/target.h b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.h similarity index 95% rename from src/main/target/IFF4_E/target.h rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.h index fb0ea6a4eb..a52e5907db 100644 --- a/src/main/target/IFF4_E/target.h +++ b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "IFRC" -#define USBD_PRODUCT_STRING "IFLIGHT SUCCEX E F4" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F4" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #define LED0_PIN PB5 @@ -105,9 +108,6 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 -#define USE_BARO -#define USE_BARO_BMP280 - #define USE_I2C #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.mk b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.mk similarity index 100% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.mk rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.mk diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/config.c b/src/main/target/IFLIGHT_SUCCEX_E_F7/config.c similarity index 100% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/config.c rename to src/main/target/IFLIGHT_SUCCEX_E_F7/config.c diff --git a/src/main/target/IFF7_TWIN_G/target.c b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.c similarity index 100% rename from src/main/target/IFF7_TWIN_G/target.c rename to src/main/target/IFLIGHT_SUCCEX_E_F7/target.c diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.h similarity index 86% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h rename to src/main/target/IFLIGHT_SUCCEX_E_F7/target.h index 372fc9d935..4a93895a28 100644 --- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h +++ b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.h @@ -20,9 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "S7X2" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F7" -#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F7" +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID #define ENABLE_DSHOT_DMAR true @@ -51,14 +53,29 @@ #define MPU6000_CS_PIN PA15 #define USE_GYRO -#define USE_GYRO_SPI_MPU6000 - #define USE_ACC + #define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 #define ACC_MPU6000_ALIGN CW180_DEG #define GYRO_MPU6000_ALIGN CW180_DEG +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define ACC_ICM20689_ALIGN CW180_DEG +#define GYRO_ICM20689_ALIGN CW180_DEG +#define ICM20689_CS_PIN PA15 +#define ICM20689_SPI_INSTANCE SPI1 + +#define USE_SPI_GYRO +#define USE_GYRO_EXTI +#define USE_ACCGYRO_BMI270 +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA15 +#define BMI270_SPI_INSTANCE SPI1 + #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/IFLIGHT_SUCCEX_E_F7/target.mk b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.mk new file mode 100644 index 0000000000..d6804d7af7 --- /dev/null +++ b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.mk @@ -0,0 +1,16 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES = VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_bmi270.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 diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.c b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.c similarity index 100% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.c rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.c diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h similarity index 93% rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h index 634e216822..5042c44db7 100644 --- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h +++ b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "IFRC" -#define USBD_PRODUCT_STRING "IFLIGHT SUCCEX E F4" +#define TARGET_MANUFACTURER_IDENTIFIER "IFRC" +#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_MINI_F4" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #define LED0_PIN PB5 @@ -105,6 +108,9 @@ #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PC12 +#define USE_BARO +#define USE_BARO_BMP280 + #define USE_I2C #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 diff --git a/src/main/target/IFF4_E/target.mk b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.mk similarity index 100% rename from src/main/target/IFF4_E/target.mk rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.mk diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk deleted file mode 100644 index b2c6c71023..0000000000 --- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_spi_mpu6000.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 diff --git a/src/main/target/IFRC_JBF7/config.c b/src/main/target/JBF7/config.c similarity index 100% rename from src/main/target/IFRC_JBF7/config.c rename to src/main/target/JBF7/config.c diff --git a/src/main/target/IFRC_JBF7/target.c b/src/main/target/JBF7/target.c similarity index 100% rename from src/main/target/IFRC_JBF7/target.c rename to src/main/target/JBF7/target.c diff --git a/src/main/target/IFRC_JBF7/target.h b/src/main/target/JBF7/target.h similarity index 100% rename from src/main/target/IFRC_JBF7/target.h rename to src/main/target/JBF7/target.h diff --git a/src/main/target/IFRC_JBF7/target.mk b/src/main/target/JBF7/target.mk similarity index 100% rename from src/main/target/IFRC_JBF7/target.mk rename to src/main/target/JBF7/target.mk 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 \ 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 \ diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 052e2a7cf5..919d307ae6 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -20,13 +20,14 @@ #pragma once +#define TARGET_MANUFACTURER_IDENTIFIER "HBRO" +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + //#define USE_TARGET_CONFIG #if defined(KAKUTEF7MINIV1) -#define TARGET_BOARD_IDENTIFIER "KF7M" -#define USBD_PRODUCT_STRING "KakuteF7 Mini V1" +#define USBD_PRODUCT_STRING "KAKUTEF7MINIV1" #else -#define TARGET_BOARD_IDENTIFIER "KTF7" -#define USBD_PRODUCT_STRING "KakuteF7" +#define USBD_PRODUCT_STRING "KAKUTEF7" #endif #define LED0_PIN PA2 @@ -37,24 +38,39 @@ #define USE_ACC #define USE_GYRO - -// ICM-20689 #define USE_ACC_SPI_ICM20689 #define USE_GYRO_SPI_ICM20689 -#define GYRO_ICM20689_ALIGN CW270_DEG -#define ACC_ICM20689_ALIGN CW270_DEG -#define MPU_INT_EXTI PE1 - -#define ICM20689_CS_PIN SPI4_NSS_PIN -#define ICM20689_SPI_INSTANCE SPI4 -#define GYRO_1_CS_PIN ICM20689_CS_PIN -#define GYRO_1_SPI_INSTANCE ICM20689_SPI_INSTANCE +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 -#define ACC_1_ALIGN ACC_ICM20689_ALIGN -#define GYRO_1_ALIGN GYRO_ICM20689_ALIGN +#define USE_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI #define USE_MPU_DATA_READY_SIGNAL -#define USE_EXTI + +#define GYRO_1_ALIGN CW270_DEG +#define ACC_1_ALIGN CW270_DEG +#define GYRO_1_CS_PIN PE4 +#define GYRO_1_EXTI_PIN PE1 +#define GYRO_1_SPI_INSTANCE SPI4 +#define MPU_INT_EXTI PE1 + +#define USE_DUAL_GYRO + +#define GYRO_2_ALIGN CW0_DEG +#define ACC_2_ALIGN CW0_DEG +#define GYRO_2_SPI_INSTANCE SPI4 + +#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PE4 +#define MPU6000_SPI_INSTANCE SPI4 + +#define ACC_ICM20689_ALIGN CW270_DEG +#define GYRO_ICM20689_ALIGN CW270_DEG +#define ICM20689_CS_PIN PE4 +#define ICM20689_SPI_INSTANCE SPI4 #define USE_VCP #define USE_USB_DETECT @@ -129,14 +145,10 @@ #define USE_SDCARD #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PD8 - #define SDCARD_SPI_INSTANCE SPI1 #define SDCARD_SPI_CS_PIN SPI1_NSS_PIN - #define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz - #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz - #define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream5 #define SDCARD_DMA_CHANNEL 3 #endif diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk index 7f1392d6a1..154eef84dc 100644 --- a/src/main/target/KAKUTEF7/target.mk +++ b/src/main/target/KAKUTEF7/target.mk @@ -7,6 +7,7 @@ endif TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_icm20689.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk b/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk new file mode 100644 index 0000000000..52b9c1d1ff --- /dev/null +++ b/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk @@ -0,0 +1 @@ +#KAKUTEF7V2.mk file diff --git a/src/main/target/KAKUTEF7HDV/target.h b/src/main/target/KAKUTEF7HDV/target.h index d33171c058..4a824688fd 100644 --- a/src/main/target/KAKUTEF7HDV/target.h +++ b/src/main/target/KAKUTEF7HDV/target.h @@ -20,21 +20,21 @@ #pragma once +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID +#define TARGET_MANUFACTURER_IDENTIFIER "HBRO" + //#define USE_TARGET_CONFIG #if defined(KAKUTEF7MINIV2) -#define TARGET_BOARD_IDENTIFIER "KF7M" -#define USBD_PRODUCT_STRING "KakuteF7 Mini V2" +#define USBD_PRODUCT_STRING "KAKUTEF7MINIV2" +#elif defined(KAKUTEF7V2) +#define USBD_PRODUCT_STRING "KAKUTEF7V2" #elif defined(KAKUTEF7V15) -#define TARGET_BOARD_IDENTIFIER "KTF7" -#define USBD_PRODUCT_STRING "Kakutef7 v15" +#define USBD_PRODUCT_STRING "KAKUTEF7V15" #else -#define TARGET_BOARD_IDENTIFIER "KTF7" -#define USBD_PRODUCT_STRING "KakuteF7 HD" +#define USBD_PRODUCT_STRING "KAKUTEF7HDV" #endif -#define TARGET_BOARD_IDENTIFIER "KTF7" -#define USBD_PRODUCT_STRING "KakuteF7" - #define LED0_PIN PA2 #define USE_BEEPER @@ -44,6 +44,14 @@ #define USE_ACC #define USE_GYRO +//ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define ACC_ICM20689_ALIGN CW270_DEG +#define GYRO_ICM20689_ALIGN CW270_DEG +#define ICM20689_CS_PIN PE4 +#define ICM20689_SPI_INSTANCE SPI4 + // MPU6000 #define USE_ACC_SPI_MPU6000 #define USE_GYRO_SPI_MPU6000 @@ -119,7 +127,7 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 -#if defined(KAKUTEF7V15) || defined(KAKUTEF7MINIV2) +#if defined(KAKUTEF7V15) || defined(KAKUTEF7V2) ||defined(KAKUTEF7MINIV2) #define CAMERA_CONTROL_PIN PB3 #define USE_MAX7456 diff --git a/src/main/target/KAKUTEF7HDV/target.mk b/src/main/target/KAKUTEF7HDV/target.mk index 8d20f30a47..79bff4a092 100644 --- a/src/main/target/KAKUTEF7HDV/target.mk +++ b/src/main/target/KAKUTEF7HDV/target.mk @@ -7,6 +7,7 @@ endif TARGET_SRC = \ drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_icm20689.c \ drivers/barometer/barometer_bmp280.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h index ed470a1e01..4eb8ef6070 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.h +++ b/src/main/target/KAKUTEF7MINIV3/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "KTF7" -#define USBD_PRODUCT_STRING "KakuteF7 Mini V3" +#define TARGET_MANUFACTURER_IDENTIFIER "HBRO" +#define USBD_PRODUCT_STRING "KAKUTEF7MINIV3" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID #define LED0_PIN PD2 @@ -29,22 +32,41 @@ #define BEEPER_PIN PC8 #define BEEPER_INVERTED -//MPU6000 #define USE_ACC #define USE_GYRO -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6000 -#define MPU_INT_EXTI PA4 -#define MPU6000_CS_PIN SPI1_NSS_PIN -#define MPU6000_SPI_INSTANCE SPI1 -#define GYRO_1_CS_PIN MPU6000_CS_PIN -#define GYRO_1_SPI_INSTANCE MPU6000_SPI_INSTANCE +#define USE_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO_1_ALIGN CW270_DEG +#define ACC_1_ALIGN CW270_DEG +#define GYRO_1_CS_PIN PB2 +#define GYRO_1_EXTI_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PA4 + +#define USE_DUAL_GYRO + +#define GYRO_2_ALIGN CW0_DEG +#define ACC_2_ALIGN CW0_DEG +#define GYRO_2_SPI_INSTANCE SPI1 -#define GYRO_MPU6000_ALIGN CW270_DEG -#define ACC_MPU6000_ALIGN CW270_DEG -#define ACC_1_ALIGN ACC_MPU6000_ALIGN -#define GYRO_1_ALIGN GYRO_MPU6000_ALIGN +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_INSTANCE SPI1 + +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define ACC_ICM42688P_ALIGN CW270_DEG +#define GYRO_ICM42688P_ALIGN CW270_DEG +#define ICM42688P_CS_PIN PB2 +#define ICM42688P_SPI_INSTANCE SPI1 #define USE_MPU_DATA_READY_SIGNAL #define USE_EXTI diff --git a/src/main/target/KAKUTEF7MINIV3/target.mk b/src/main/target/KAKUTEF7MINIV3/target.mk index e0e4af6d5c..6a30ffc432 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.mk +++ b/src/main/target/KAKUTEF7MINIV3/target.mk @@ -3,6 +3,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_bmp280.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MAMBAF405US/MAMBAF405US_I2C.mk b/src/main/target/MAMBAF405US/MAMBAF405US_I2C.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/DIAT_MAMBAF405US/config.c b/src/main/target/MAMBAF405US/config.c similarity index 100% rename from src/main/target/DIAT_MAMBAF405US/config.c rename to src/main/target/MAMBAF405US/config.c diff --git a/src/main/target/DIAT_MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c similarity index 100% rename from src/main/target/DIAT_MAMBAF405US/target.c rename to src/main/target/MAMBAF405US/target.c diff --git a/src/main/target/DIAT_MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h similarity index 98% rename from src/main/target/DIAT_MAMBAF405US/target.h rename to src/main/target/MAMBAF405US/target.h index d2ffbb529c..8dcd92d716 100644 --- a/src/main/target/DIAT_MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -20,7 +20,7 @@ #pragma once -#if defined(DIAT_MAMBAF405US_I2C) +#if defined(MAMBAF405US_I2C) #define TARGET_BOARD_IDENTIFIER "S405" #define USBD_PRODUCT_STRING "MAMBAF405US I2C" #else @@ -79,7 +79,7 @@ #define USE_I2C #define USE_I2C_DEVICE_2 #define I2C_DEVICE (I2CDEV_2) -#if defined(DIAT_MAMBAF405US_I2C) +#if defined(MAMBAF405US_I2C) #define I2C2_SCL PB8 // SCL pad PB10, shared with UART3TX #define I2C2_SDA PB9 // SDA pad PB11, shared with UART3RX #else diff --git a/src/main/target/DIAT_MAMBAF405US/target.mk b/src/main/target/MAMBAF405US/target.mk similarity index 100% rename from src/main/target/DIAT_MAMBAF405US/target.mk rename to src/main/target/MAMBAF405US/target.mk diff --git a/src/main/target/MAMBAF405_2022B/target.c b/src/main/target/MAMBAF405_2022B/target.c new file mode 100644 index 0000000000..37e46483ec --- /dev/null +++ b/src/main/target/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/MAMBAF405_2022B/target.h b/src/main/target/MAMBAF405_2022B/target.h new file mode 100644 index 0000000000..2e8faaa864 --- /dev/null +++ b/src/main/target/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/MAMBAF405_2022B/target.mk b/src/main/target/MAMBAF405_2022B/target.mk new file mode 100644 index 0000000000..775a554519 --- /dev/null +++ b/src/main/target/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. diff --git a/src/main/target/MAMBAF722_2022A/target.c b/src/main/target/MAMBAF722_2022A/target.c new file mode 100644 index 0000000000..dc954c0ec4 --- /dev/null +++ b/src/main/target/MAMBAF722_2022A/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: 0808fa2 + +#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(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // led +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/MAMBAF722_2022A/target.h b/src/main/target/MAMBAF722_2022A/target.h new file mode 100644 index 0000000000..101c7c5fe5 --- /dev/null +++ b/src/main/target/MAMBAF722_2022A/target.h @@ -0,0 +1,156 @@ +/* + * 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: 0808fa2 + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "DIAT" +#define USBD_PRODUCT_STRING "MAMBAF722_2022A" + +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 +#define USE_BARO_DPS310 +#define USE_BARO + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#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 PB2 +#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_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO_1_ALIGN CW180_DEG +#define ACC_1_ALIGN CW180_DEG +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PC4 + +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 + +#define USE_UART1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 +#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_TX_PIN PA0 +#define UART4_RX_PIN PA1 +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#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 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_ADC +#define VBAT_ADC_PIN PC1 +#define CURRENT_METER_ADC_PIN PC3 +#define ADC3_DMA_OPT 0 +#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 115 +#define ADC_INSTANCE ADC3 + +#define ENABLE_DSHOT_DMAR true + +#define PINIO1_PIN PC2 +#define PINIO2_PIN PC0 +#define PINIO1_BOX 0 +#define PINIO2_BOX 40 +#define PINIO1_CONFIG 129 +#define PINIO2_CONFIG 129 + +#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 + +#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) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/MAMBAF722_2022A/target.mk b/src/main/target/MAMBAF722_2022A/target.mk new file mode 100644 index 0000000000..6d5a422d74 --- /dev/null +++ b/src/main/target/MAMBAF722_2022A/target.mk @@ -0,0 +1,14 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_mpu6000.c \ +drivers/accgyro/accgyro_spi_bmi270.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 0808fa2 diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 006cbe36cd..0af5b9d9fc 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -20,8 +20,11 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "MKF4" -#define USBD_PRODUCT_STRING "Matek F405 SE" +#define TARGET_MANUFACTURER_IDENTIFIER "MTKS" +#define USBD_PRODUCT_STRING "MATEKF405SE" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID #define LED0_PIN PA14 #define LED1_PIN PA13 @@ -82,16 +85,16 @@ #define USE_I2C // Useful for MATEKF405_OSD, since it does not have the SCL / SDA pads #define USE_I2C_DEVICE_1 -#define I2C_DEVICE (I2CDEV_1) +#define I2C_DEVICE_1 (I2CDEV_1) #define I2C1_SCL PB8 // S4 pad #define I2C3_SDA PB9 // S6 pad #define BARO_I2C_INSTANCE (I2CDEV_1) #define USE_I2C_DEVICE_2 -#define I2C_DEVICE (I2CDEV_2) +#define I2C_DEVICE_2 (I2CDEV_2) #define I2C2_SCL PB10 // SCL pad #define I2C2_SDA PB11 // SDA pad -#define BARO_I2C_INSTANCE (I2CDEV_1) +#define MAG_I2C_INSTANCE (I2CDEV_2) #define USE_BARO #define USE_BARO_BMP280 diff --git a/src/main/target/MATEKF411RX/target.h b/src/main/target/MATEKF411RX/target.h index 25b100780c..832ad67e72 100644 --- a/src/main/target/MATEKF411RX/target.h +++ b/src/main/target/MATEKF411RX/target.h @@ -21,19 +21,22 @@ #pragma once #if defined(CRAZYBEEF4FR) -#define TARGET_BOARD_IDENTIFIER "C4FR" -#define USBD_PRODUCT_STRING "CrazyBee F4 FR" +#define TARGET_MANUFACTURER_IDENTIFIER "HAMO" +#define USBD_PRODUCT_STRING "CRAZYBEEF4FR" #elif defined(CRAZYBEEF4FS) -#define TARGET_BOARD_IDENTIFIER "C4FS" -#define USBD_PRODUCT_STRING "CrazyBee F4 FS" +#define TARGET_MANUFACTURER_IDENTIFIER "HAMO" +#define USBD_PRODUCT_STRING "CRAZYBEEF4FS" #elif defined(CRAZYBEEF4DX) -#define TARGET_BOARD_IDENTIFIER "C4DX" -#define USBD_PRODUCT_STRING "CrazyBee F4 DX" +#define TARGET_MANUFACTURER_IDENTIFIER "HAMO" +#define USBD_PRODUCT_STRING "CRAZYBEEF4DX" #else -#define TARGET_BOARD_IDENTIFIER "M41R" -#define USBD_PRODUCT_STRING "MATEKF411RX" +#define TARGET_MANUFACTURER_IDENTIFIER "MTKS" +#define USBD_PRODUCT_STRING "MATEKF411RX" #endif +#define FC_TARGET_MCU STM32F411 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S411" // generic ID + #define LED0_PIN PC13 #define USE_BEEPER @@ -43,6 +46,16 @@ #define USE_SPI // *************** SPI1 Gyro & ACC ********************** +#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 USE_ACCGYRO_BMI270 + #define USE_SPI_DEVICE_1 #define SPI1_SCK_PIN PA5 #define SPI1_MISO_PIN PA6 @@ -57,27 +70,36 @@ #define MPU_INT_EXTI PA1 #define USE_MPU_DATA_READY_SIGNAL -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 -#define USE_GYRO_SPI_ICM20689 +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_SPI_INSTANCE SPI1 + +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_INSTANCE SPI1 #if defined(CRAZYBEEF4FS) || defined(CRAZYBEEF4FR) || defined(CRAZYBEEF4DX) -#define GYRO_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG #define GYRO_ICM20689_ALIGN CW90_DEG +#define GYRO_ICM42688P_ALIGN CW90_DEG +#define GYRO_BMI270_ALIGN CW90_DEG #else -#define GYRO_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG #define GYRO_ICM20689_ALIGN CW180_DEG +#define GYRO_ICM42688P_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG #endif -#define USE_ACC -#define USE_ACC_SPI_MPU6000 -#define USE_ACC_SPI_ICM20689 + #if defined(CRAZYBEEF4FS) || defined(CRAZYBEEF4FR) || defined(CRAZYBEEF4DX) -#define ACC_MPU6000_ALIGN CW90_DEG +#define ACC_MPU6000_ALIGN CW90_DEG #define ACC_ICM20689_ALIGN CW90_DEG +#define ACC_ICM42688P_ALIGN CW90_DEG +#define ACC_BMI270_ALIGN CW90_DEG #else -#define ACC_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG #define ACC_ICM20689_ALIGN CW180_DEG +#define ACC_ICM42688P_ALIGN CW180_DEG +#define ACC_BMI270_ALIGN CW180_DEG #endif + // *************** SPI2 OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/MATEKF411RX/target.mk b/src/main/target/MATEKF411RX/target.mk index df79c2e027..e7b567997d 100644 --- a/src/main/target/MATEKF411RX/target.mk +++ b/src/main/target/MATEKF411RX/target.mk @@ -4,14 +4,16 @@ FEATURES += VCP SDCARD TARGET_SRC = \ drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ + drivers/accgyro/accgyro_spi_bmi270.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 ifeq ($(TARGET), CRAZYBEEF4FS) TARGET_SRC += \ diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 61945caf16..214d4cd2f7 100644 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -138,5 +138,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 10 +#define USABLE_TIMER_CHANNEL_COUNT 11 #define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(9)|TIM_N(11) ) 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 \ 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..3f85579094 100644 --- a/src/main/target/NBDHMBF41S/config.c +++ b/src/main/target/NBDHMBF41S/config.c @@ -17,7 +17,7 @@ * * If not, see . */ -/* + #include #include #include @@ -38,7 +38,7 @@ #include "fc/config.h" #include "fc/controlrate_profile.h" -#include "fc/core.h" +#include "fc/fc_core.h" #include "fc/rc_adjustments.h" #include "fc/rc_modes.h" #include "fc/rc_controls.h" @@ -49,18 +49,19 @@ #include "pg/vcd.h" #include "pg/rx.h" -#include "pg/motor.h" -#include "pg/vtx_table.h" +//#include "pg/motor.h" +#include "io/motors.h" +//#include "pg/vtx_table.h" #include "rx/rx.h" #include "rx/cc2500_frsky_common.h" #include "pg/rx.h" #include "pg/rx_spi.h" -#include "pg/rx_spi_cc2500.h" +#include "drivers/rx/rx_cc2500.h" #include "pg/vcd.h" -#include "osd/osd.h" +#include "io/osd.h" #include "io/serial.h" #include "io/vtx.h" @@ -74,14 +75,14 @@ void targetConfiguration(void) { - osdConfigMutable()->item_pos[OSD_CRAFT_NAME] = OSD_POS(9, 10) | OSD_PROFILE_1_FLAG; - osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(23, 9) | OSD_PROFILE_1_FLAG; - osdConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(2, 9) | OSD_PROFILE_1_FLAG; - osdConfigMutable()->item_pos[OSD_FLYMODE] = OSD_POS(17, 9) | OSD_PROFILE_1_FLAG; - osdConfigMutable()->item_pos[OSD_VTX_CHANNEL] = OSD_POS(9, 9) | OSD_PROFILE_1_FLAG; - osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(2, 10) | OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_CRAFT_NAME] = OSD_POS(9, 10); //| OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(23, 9); //| OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(2, 9); //| OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_FLYMODE] = OSD_POS(17, 9); //| OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_VTX_CHANNEL] = OSD_POS(9, 9); //| OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(2, 10); //| OSD_PROFILE_1_FLAG; osdConfigMutable()->item_pos[OSD_WARNINGS] = OSD_POS(9, 10); - osdConfigMutable()->item_pos[OSD_CURRENT_DRAW] = OSD_POS(22,10) | OSD_PROFILE_1_FLAG; + osdConfigMutable()->item_pos[OSD_CURRENT_DRAW] = OSD_POS(22,10); //| OSD_PROFILE_1_FLAG; batteryConfigMutable()->batteryCapacity = 250; @@ -113,11 +114,17 @@ void targetConfiguration(void) strcpy(pilotConfigMutable()->name, "Humming Bird"); gyroConfigMutable()->gyro_lowpass_type = FILTER_PT1; - gyroConfigMutable()->gyro_lowpass_hz = 200; - gyroConfigMutable()->gyro_lowpass2_hz = 200; + 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] = 500; + gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = 500; + gyroConfigMutable()->gyro_lowpass2_hz[YAW] = 500; +#endif gyroConfigMutable()->yaw_spin_threshold = 1950; - gyroConfigMutable()->dyn_lpf_gyro_min_hz = 160; - gyroConfigMutable()->dyn_lpf_gyro_max_hz = 400; + gyroConfigMutable()->dyn_notch_min_hz = 160; + gyroConfigMutable()->dyn_notch_max_hz = 400; rxConfigMutable()->mincheck = 1075; rxConfigMutable()->maxcheck = 1900; rxConfigMutable()->rc_smoothing_type = RC_SMOOTHING_TYPE_FILTER; @@ -125,32 +132,34 @@ void targetConfiguration(void) rxConfigMutable()->rssi_channel = 9; motorConfigMutable()->digitalIdleOffsetValue = 1000; motorConfigMutable()->dev.useBurstDshot = true; - motorConfigMutable()->dev.useDshotTelemetry = false; + //motorConfigMutable()->dev.useDshotTelemetry = false; motorConfigMutable()->motorPoleCount = 12; motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT600; batteryConfigMutable()->batteryCapacity = 300; - batteryConfigMutable()->vbatmaxcellvoltage = 450; - batteryConfigMutable()->vbatfullcellvoltage = 400; - batteryConfigMutable()->vbatmincellvoltage = 290; - batteryConfigMutable()->vbatwarningcellvoltage = 320; + batteryConfigMutable()->vbatmaxcellvoltage = 45; + batteryConfigMutable()->vbatfullcellvoltage = 42; + batteryConfigMutable()->vbatmincellvoltage = 29; + batteryConfigMutable()->vbatwarningcellvoltage = 32; voltageSensorADCConfigMutable(0)->vbatscale = 110; mixerConfigMutable()->yaw_motors_reversed = false; mixerConfigMutable()->crashflip_motor_percent = 0; imuConfigMutable()->small_angle = 180; pidConfigMutable()->pid_process_denom = 1; pidConfigMutable()->runaway_takeoff_prevention = true; - //osdConfigMutable()->enabledWarnings &= ~(1 << OSD_WARNING_CORE_TEMPERATURE); + osdConfigMutable()->enabledWarnings &= ~(1 << OSD_WARNING_CORE_TEMPERATURE); osdConfigMutable()->cap_alarm = 2200; pidProfilesMutable(0)->dterm_filter_type = FILTER_PT1; - pidProfilesMutable(0)->dyn_lpf_dterm_min_hz = 56; - pidProfilesMutable(0)->dyn_lpf_dterm_max_hz = 136; - pidProfilesMutable(0)->dterm_lowpass_hz = 150; - pidProfilesMutable(0)->dterm_lowpass2_hz = 120; - pidProfilesMutable(0)->dterm_notch_cutoff = 0; - pidProfilesMutable(0)->vbatPidCompensation = true; + //pidProfilesMutable(0)->dyn_lpf_dterm_min_hz = 56; + //pidProfilesMutable(0)->dyn_lpf_dterm_max_hz = 136; + pidProfilesMutable(0)->dFilter[ROLL].dLpf = 150; + pidProfilesMutable(0)->dFilter[PITCH].dLpf = 150; + pidProfilesMutable(0)->dFilter[YAW].dLpf = 150; + //pidProfilesMutable(0)->dterm_lowpass2_hz = 120; + //pidProfilesMutable(0)->dterm_notch_cutoff = 0; + //pidProfilesMutable(0)->vbatPidCompensation = true; pidProfilesMutable(0)->iterm_rotation = true; - pidProfilesMutable(0)->itermThrottleThreshold = 250; + //pidProfilesMutable(0)->itermThrottleThreshold = 250; pidProfilesMutable(0)->yawRateAccelLimit = 0; pidProfilesMutable(0)->pidSumLimit = 500; pidProfilesMutable(0)->pidSumLimitYaw = 400; @@ -166,16 +175,16 @@ void targetConfiguration(void) pidProfilesMutable(0)->pid[PID_YAW].I = 55; pidProfilesMutable(0)->pid[PID_YAW].D = 0; pidProfilesMutable(0)->pid[PID_YAW].F = 0; - pidProfilesMutable(0)->pid[PID_LEVEL].P = 70; - pidProfilesMutable(0)->pid[PID_LEVEL].I = 70; - pidProfilesMutable(0)->pid[PID_LEVEL].D = 100; + //pidProfilesMutable(0)->pid[PID_LEVEL].P = 70; + //pidProfilesMutable(0)->pid[PID_LEVEL].I = 70; + //pidProfilesMutable(0)->pid[PID_LEVEL].D = 100; pidProfilesMutable(0)->levelAngleLimit = 85; pidProfilesMutable(0)->horizon_tilt_effect = 75; - pidProfilesMutable(0)->d_min[FD_ROLL] = 20; - pidProfilesMutable(0)->d_min[FD_PITCH] = 18; - pidProfilesMutable(0)->d_min_gain = 25; - pidProfilesMutable(0)->d_min_advance = 1; - pidProfilesMutable(0)->horizon_tilt_expert_mode = false; + //pidProfilesMutable(0)->d_min[FD_ROLL] = 20; + //pidProfilesMutable(0)->d_min[FD_PITCH] = 18; + //pidProfilesMutable(0)->d_min_gain = 25; + //pidProfilesMutable(0)->d_min_advance = 1; + //pidProfilesMutable(0)->horizon_tilt_expert_mode = false; controlRateProfilesMutable(0)->rcRates[FD_YAW] = 100; controlRateProfilesMutable(0)->rates[FD_ROLL] = 73; @@ -184,25 +193,24 @@ void targetConfiguration(void) controlRateProfilesMutable(0)->rcExpo[FD_ROLL] = 15; controlRateProfilesMutable(0)->rcExpo[FD_PITCH] = 15; controlRateProfilesMutable(0)->rcExpo[FD_YAW] = 15; - controlRateProfilesMutable(0)->dynThrPID = 65; + //controlRateProfilesMutable(0)->dynThrPID = 65; controlRateProfilesMutable(0)->tpa_breakpoint = 1250; - ledStripStatusModeConfigMutable()->ledConfigs[0] = DEFINE_LED(7, 7, 8, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); - ledStripStatusModeConfigMutable()->ledConfigs[1] = DEFINE_LED(8, 7, 13, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); - ledStripStatusModeConfigMutable()->ledConfigs[2] = DEFINE_LED(9, 7, 11, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); - ledStripStatusModeConfigMutable()->ledConfigs[3] = DEFINE_LED(10, 7, 4, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); + ledStripConfigMutable()->ledConfigs[0] = DEFINE_LED(7, 7, 8, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); + ledStripConfigMutable()->ledConfigs[1] = DEFINE_LED(8, 7, 13, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); + ledStripConfigMutable()->ledConfigs[2] = DEFINE_LED(9, 7, 11, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); + ledStripConfigMutable()->ledConfigs[3] = DEFINE_LED(10, 7, 4, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0); do { // T8SG uint8_t defaultTXHopTable[50] = {0,30,60,91,120,150,180,210,5,35,65,95,125,155,185,215,10,40,70,100,130,160,190,221,15,45,75,105,135,165,195,225,20,50,80,110,140,170,200,230,25,55,85,115,145,175,205,0,0,0}; - rxCc2500SpiConfigMutable()->bindOffset = 33; - rxCc2500SpiConfigMutable()->bindTxId[0] = 198; - rxCc2500SpiConfigMutable()->bindTxId[1] = 185; + rxFrSkySpiConfigMutable()->bindOffset = 33; + rxFrSkySpiConfigMutable()->bindTxId[0] = 198; + rxFrSkySpiConfigMutable()->bindTxId[1] = 185; for (uint8_t i = 0; i < 50; i++) { - rxCc2500SpiConfigMutable()->bindHopData[i] = defaultTXHopTable[i]; + rxFrSkySpiConfigMutable()->bindHopData[i] = defaultTXHopTable[i]; } } while (0); serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP; } #endif -*/ 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/main/target/NBD_INFINITYAIOV2/target.c b/src/main/target/NBD_INFINITYAIOV2/target.c new file mode 100644 index 0000000000..eee0de7bb5 --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2/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 . + */ + +// 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(TIM3, CH1, PC6, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM4, CH2, PD13, TIM_USE_ANY, 0, 0), +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/NBD_INFINITYAIOV2/target.h b/src/main/target/NBD_INFINITYAIOV2/target.h new file mode 100644 index 0000000000..0d042c69ac --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2/target.h @@ -0,0 +1,136 @@ +/* + * 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 + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "NEBD" +#define USBD_PRODUCT_STRING "NBD_INFINITYAIOV2" + +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + +#define USE_ACC +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_SPI_GYRO + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC0 +#define LED_STRIP_PIN PA9 +#define USE_BEEPER +#define BEEPER_PIN PD13 +#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_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PD6 +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 + +#define GYRO_1_ALIGN CW180_DEG +#define ACC_1_ALIGN CW180_DEG +#define GYRO_1_CS_PIN PE11 +#define GYRO_1_EXTI_PIN PB1 +#define GYRO_1_SPI_INSTANCE SPI4 +#define MPU_INT_EXTI PB1 + +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_SPI_GYRO +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PE11 +#define BMI270_SPI_INSTANCE SPI4 + +#define USE_UART1 +#define UART1_RX_PIN PB7 +#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_UART5 +#define UART5_RX_PIN PD2 +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 +#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 I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define FLASH_CS_PIN PB0 +#define FLASH_SPI_INSTANCE SPI1 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_SPI_INSTANCE SPI3 + +#define VBAT_ADC_PIN PC1 +#define CURRENT_METER_ADC_PIN PC2 +#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 DEFAULT_CURRENT_METER_SCALE 230 + +#define ENABLE_DSHOT_DMAR true + +#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 +// 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 + +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/NBD_INFINITYAIOV2/target.mk b/src/main/target/NBD_INFINITYAIOV2/target.mk new file mode 100644 index 0000000000..6d826148cc --- /dev/null +++ b/src/main/target/NBD_INFINITYAIOV2/target.mk @@ -0,0 +1,20 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_bmi270.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/max7456.c \ +drivers/barometer/barometer_bmp085.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/barometer/barometer_fake.c \ +drivers/barometer/barometer_lps.c \ +drivers/barometer/barometer_ms5611.c \ +drivers/barometer/barometer_qmp6988.c \ + +# notice - this file was programmatically generated and may be incomplete. + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 4cb7ad1 diff --git a/src/main/target/TMTR_TMOTORF7/target.c b/src/main/target/NBD_INFINITYAIOV2PRO/target.c similarity index 61% rename from src/main/target/TMTR_TMOTORF7/target.c rename to src/main/target/NBD_INFINITYAIOV2PRO/target.c index 847810cf45..b0d2fbf100 100644 --- a/src/main/target/TMTR_TMOTORF7/target.c +++ b/src/main/target/NBD_INFINITYAIOV2PRO/target.c @@ -17,6 +17,9 @@ * * If not, see . */ + +#include + #include "platform.h" #include "drivers/io.h" @@ -25,15 +28,10 @@ #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(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(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 \ diff --git a/src/main/target/NERO/target.c b/src/main/target/NERO/target.c index 32b61c4a52..ca539b0c66 100644 --- a/src/main/target/NERO/target.c +++ b/src/main/target/NERO/target.c @@ -28,13 +28,13 @@ #include "drivers/timer_def.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM3, CH2, PC7, TIM_USE_PPM, 0, 0 ), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0 ), - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1 ), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_LED, 0, 0 ), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0 ), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0 ), + DEF_TIM(TIM3, CH2, PC7, TIM_USE_PPM, 0, 0), + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // motor 5 and LED_STRIP + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 8 }; diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h index 3c11c6dac5..2f6db626aa 100644 --- a/src/main/target/NERO/target.h +++ b/src/main/target/NERO/target.h @@ -19,17 +19,30 @@ */ #pragma once -#define TARGET_BOARD_IDENTIFIER "NERO" +#define TARGET_MANUFACTURER_IDENTIFIER "BKMN" +#define USBD_PRODUCT_STRING "NERO" -#define USBD_PRODUCT_STRING "NERO" +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_ICM20602 // detected by MPU6500 code +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20602 // detected by MPU6500 code +#define USE_SDCARD #define HW_PIN PB2 #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define USE_LED #define LED0_PIN PB6 #define LED1_PIN PB5 #define LED2_PIN PB4 +#define LED_STRIP_PIN PB0 // Shared with MOTOR5_PIN +#define MOTOR5_PIN PB0 // Shared with LED_STRIP_PIN #define USE_BEEPER #define BEEPER_PIN PC1 @@ -55,7 +68,7 @@ #define GYRO_MPU6500_ALIGN CW0_DEG #define USE_SDCARD - +#define USE_SDCARD_SDIO #define SDCARD_DETECT_INVERTED #define SDCARD_DETECT_PIN PD2 #define SDCARD_SPI_INSTANCE SPI3 @@ -96,6 +109,7 @@ #define SERIAL_PORT_COUNT 6 +#define ENABLE_DSHOT_DMAR true #define USE_ESCSERIAL #define ESCSERIAL_TIMER_TX_PIN PC7 // (Hardware=0, PPM) @@ -121,10 +135,16 @@ #define USE_ADC #define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PA4 +#define ADC1_DMA_OPT 1 +#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 ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART6 diff --git a/src/main/target/NERO/target.mk b/src/main/target/NERO/target.mk index e2e1a265d5..c648832f84 100644 --- a/src/main/target/NERO/target.mk +++ b/src/main/target/NERO/target.mk @@ -1,6 +1,10 @@ F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP +FEATURES += VCP SDCARD TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_mpu6500.c +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_mpu6500.c \ +drivers/accgyro/accgyro_spi_mpu6500.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/max7456.c \ diff --git a/src/main/target/TEBS_PODRACERAIO/target.c b/src/main/target/PODRACERAIO/target.c similarity index 100% rename from src/main/target/TEBS_PODRACERAIO/target.c rename to src/main/target/PODRACERAIO/target.c diff --git a/src/main/target/TEBS_PODRACERAIO/target.h b/src/main/target/PODRACERAIO/target.h similarity index 100% rename from src/main/target/TEBS_PODRACERAIO/target.h rename to src/main/target/PODRACERAIO/target.h diff --git a/src/main/target/TEBS_PODRACERAIO/target.mk b/src/main/target/PODRACERAIO/target.mk similarity index 100% rename from src/main/target/TEBS_PODRACERAIO/target.mk rename to src/main/target/PODRACERAIO/target.mk diff --git a/src/main/target/PYRODRONEF7/target.c b/src/main/target/PYRODRONEF7/target.c index 64eff72d67..79fc418786 100644 --- a/src/main/target/PYRODRONEF7/target.c +++ b/src/main/target/PYRODRONEF7/target.c @@ -28,16 +28,23 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION - DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // pin B03: TIM2 CH2 (AF1) // USE FOR CAMERA CONTROL - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // D2-ST2/D2-ST4 MOTOR4 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST4 MOTOR5 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // D2-ST7 MOTOR7 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // pin B06: TIM4 CH1 (AF2) // D1-ST0 MOTOR1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // pin B07: TIM4 CH2 (AF2) // D1-ST3 MOTOR2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // pin B08: TIM4 CH3 (AF2) // D1-ST7 MOTOR3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // pin C08: TIM8 CH3 (AF3) // D2-ST2/D2-ST4 MOTOR4 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // pin A01: TIM5 CH2 (AF2) // D1-ST4 MOTOR5 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // pin B09: TIM4 CH4 (AF2) // NONE TIM4_UP_D1-ST6 MOTOR6 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // pin C09: TIM8 CH4 (AF3) // D2-ST7 MOTOR7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // pin B01: TIM3 CH4 (AF2) // D1-ST2 LED/MOTOR5 + + DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), // pin A03: TIM9 CH2 (AF3) + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_ANY, 0, 0), // pin B00: TIM1 CH2N (AF1) + DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // pin A00: TIM5 CH1 (AF2) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_ANY, 0, 0), // pin C06: TIM3 CH1 (AF2) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // pin C07: TIM8 CH2 (AF3) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_ANY, 0, 0), // pin B05: TIM3 CH2 (AF2) }; \ No newline at end of file diff --git a/src/main/target/PYRODRONEF7/target.h b/src/main/target/PYRODRONEF7/target.h index 8b8ef34c0e..d1f57146b4 100644 --- a/src/main/target/PYRODRONEF7/target.h +++ b/src/main/target/PYRODRONEF7/target.h @@ -132,5 +132,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 6 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) ) +#define USABLE_TIMER_CHANNEL_COUNT 15 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) |TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/PYRODRONEF7/target.mk b/src/main/target/PYRODRONEF7/target.mk index 3bae3aba77..6a383ad58a 100644 --- a/src/main/target/PYRODRONEF7/target.mk +++ b/src/main/target/PYRODRONEF7/target.mk @@ -9,4 +9,5 @@ TARGET_SRC = \ drivers/light_ws2811strip_hal.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ + drivers/pinio.c \ drivers/max7456.c diff --git a/src/main/target/RUSHBLADEF7/target.c b/src/main/target/RUSHBLADEF7/target.c index 5cd05775bc..fefead3d9e 100644 --- a/src/main/target/RUSHBLADEF7/target.c +++ b/src/main/target/RUSHBLADEF7/target.c @@ -1,41 +1,45 @@ /* - * This file is part of Cleanflight and Betaflight. + * This file is part of EmuFlight. It is derived from 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. + * 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. * - * 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. + * You should have received a copy of the GNU General Public + * License along with this software. * * If not, see . */ -#include +// This resource file generated using https://github.com/nerdCopter/target-convert +// Commit: c4eda1b +#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_LED, 0, 0), // PPM&SBUS - - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S4 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S5 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S6 - - DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // LED STRIP + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // cam ctrl }; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/RUSHBLADEF7/target.h b/src/main/target/RUSHBLADEF7/target.h index 8559f4f88d..102932a3df 100644 --- a/src/main/target/RUSHBLADEF7/target.h +++ b/src/main/target/RUSHBLADEF7/target.h @@ -1,148 +1,155 @@ /* - * This file is part of Cleanflight and Betaflight. + * This file is part of EmuFlight. It is derived from 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. + * 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. * - * 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. + * 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: c4eda1b + #pragma once -#define TARGET_BOARD_IDENTIFIER "RSF7" -#define USBD_PRODUCT_STRING "RUSHBLADE F7" +#define TARGET_MANUFACTURER_IDENTIFIER "RUSH" +#define USBD_PRODUCT_STRING "BLADE_F7" -#define ENABLE_DSHOT_DMAR true +#define FC_TARGET_MCU STM32F7X2 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID -#define LED0_PIN PB10 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_SPI_GYRO +#define USE_BARO + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_OSD +#define USE_LED +#define LED0_PIN PB10 +#define LED_STRIP_PIN PA15 #define USE_BEEPER -#define BEEPER_PIN PB2 +#define BEEPER_PIN PB2 #define BEEPER_INVERTED -//#define BEEPER_PWM_HZ 1100 +#define BEEPER_PWM_HZ 1100 +#define CAMERA_CONTROL_PIN PA8 -#define USE_EXTI -#define MPU_INT_EXTI PA4 -#define USE_MPU_DATA_READY_SIGNAL +#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_ACC -#define USE_GYRO -//------MPU6000 -#define MPU6000_CS_PIN PC4 -#define MPU6000_SPI_INSTANCE SPI1 +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI -#define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define USE_MPU_DATA_READY_SIGNAL -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_1_ALIGN CW270_DEG +#define ACC_1_ALIGN CW270_DEG +#define GYRO_1_CS_PIN PC4 +#define GYRO_1_EXTI_PIN PA4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PA4 -#define USE_ACC_MPU6000 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_MPU6000 -#define USE_GYRO_SPI_MPU6000 - -#define USE_BARO -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 +#define ACC_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PC4 +#define MPU6000_SPI_INSTANCE SPI1 -#define USE_MAG -#define USE_MAG_HMC5883 +#define ACC_ICM42688P_ALIGN CW270_DEG +#define GYRO_ICM42688P_ALIGN CW270_DEG +#define ICM42688P_CS_PIN PC4 +#define ICM42688P_SPI_INSTANCE SPI1 -#define USE_VCP #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 UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define UART3_TX_PIN PC10 -#define UART3_RX_PIN PC11 - -#define UART4_TX_PIN PA0 -#define UART4_RX_PIN PA1 - -#define UART5_TX_PIN PC12 -#define UART5_RX_PIN PD2 - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 8 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 +#define SERIAL_PORT_COUNT 6 +//#define USE_SOFTSERIAL1 //old defines had softserial, maybe in error +//#define USE_SOFTSERIAL2 +//#define SERIAL_PORT_COUNT 8 #define USE_I2C #define USE_I2C_DEVICE_1 -#define I2C_DEVICE I2CDEV_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -#define USE_SPI -#define USE_SPI_DEVICE_1 //GYRO/ACC -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define USE_SPI_DEVICE_2 //MAX7456 -#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_MAX7456 -#define MAX7456_SPI_INSTANCE SPI2 -#define MAX7456_SPI_CS_PIN PB11 +#define I2C_DEVICE (I2CDEV_1) +#define BARO_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 +#define FLASH_CS_PIN PB12 +#define FLASH_SPI_INSTANCE SPI2 #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 - -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC3_DMA_STREAM DMA2_Stream0 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 +#define MAX7456_SPI_CS_PIN PB11 +#define MAX7456_SPI_INSTANCE SPI2 +#define USE_ADC +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define ADC1_DMA_OPT 1 +#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 DEFAULT_CURRENT_METER_SCALE 179 -#define USE_OSD -#define USE_LED_STRIP +#define ENABLE_DSHOT_DMAR true -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES FEATURE_OSD -#define SERIALRX_UART SERIAL_PORT_USART2 -#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_PORTD (BIT(2)) //old defines used this instead -#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define USABLE_TIMER_CHANNEL_COUNT 10 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) -#define USABLE_TIMER_CHANNEL_COUNT 9 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9) ) +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/RUSHBLADEF7/target.mk b/src/main/target/RUSHBLADEF7/target.mk index eb35ec20ee..512a00a52e 100644 --- a/src/main/target/RUSHBLADEF7/target.mk +++ b/src/main/target/RUSHBLADEF7/target.mk @@ -2,9 +2,18 @@ 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/compass/compass_hmc5883l.c \ - drivers/max7456.c +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/compass/compass_hmc5883l.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/max7456.c \ + +# notice - this file was programmatically generated and may be incomplete. +# drivers for ms5611 & compass manually added + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: c4eda1b 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 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 diff --git a/src/main/target/CRASHTESTF7/config.c b/src/main/target/SKYSTARSF7HDPRO/config.c similarity index 89% rename from src/main/target/CRASHTESTF7/config.c rename to src/main/target/SKYSTARSF7HDPRO/config.c index b9c6b5aea5..30086932e3 100644 --- a/src/main/target/CRASHTESTF7/config.c +++ b/src/main/target/SKYSTARSF7HDPRO/config.c @@ -18,19 +18,19 @@ * If not, see . */ -#include #include -#include #include "platform.h" +#define USE_TARGET_CONFIG + +#include "io/serial.h" #include "pg/pinio.h" #include "pg/piniobox.h" - -#ifdef USE_TARGET_CONFIG +#include "target.h" void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = 40; + pinioConfigMutable()->config[0] = 129; } -#endif 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 diff --git a/src/main/target/SPEEDYBEEF405V3/target.c b/src/main/target/SPEEDYBEEF405V3/target.c new file mode 100644 index 0000000000..d54e0e4104 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/target.c @@ -0,0 +1,47 @@ +/* + * 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: 1bce24c + +#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(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // ppm + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl + DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // led +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEEF405V3/target.h b/src/main/target/SPEEDYBEEF405V3/target.h new file mode 100644 index 0000000000..bc440ac623 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/target.h @@ -0,0 +1,153 @@ +/* + * 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: 1bce24c + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "SPBE" +#define USBD_PRODUCT_STRING "SPEEDYBEEF405V3" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_BARO_DPS310 +#define USE_BARO +#define USE_SDCARD_SPI +#define USE_SPI_GYRO +#define USE_BARO + +#define USE_VCP +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC8 +#define LED_STRIP_PIN PC9 +#define USE_BEEPER +#define BEEPER_PIN PC5 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PB3 + +#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_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define GYRO_1_ALIGN CW0_DEG +#define ACC_1_ALIGN CW0_DEG +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PC4 + +#define USE_SPI_GYRO +#define ACC_BMI270_ALIGN CW0_DEG +#define GYRO_BMI270_ALIGN CW0_DEG +#define BMI270_CS_PIN PA4 +#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 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 USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define MSP_DISPLAYPORT_UART SERIAL_PORT_USART1 +#define SERIALRX_UART SERIAL_PORT_USART2 +#define SERIAL_PORT_COUNT 7 + +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C_DEVICE (I2CDEV_2) +#define MAG_I2C_INSTANCE (I2CDEV_2) +#define BARO_I2C_INSTANCE (I2CDEV_2) +#define DASHBOARD_I2C_INSTANCE (I2CDEV_2) +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_SDCARD_SDIO +#define SDCARD_SPI_CS_PIN PA15 +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_DMA_CHANNEL 0 +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4 //# SPI_MOSI 2: DMA1 Stream 4 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 VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define ADC1_DMA_OPT 0 +#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 386 + +#define ENABLE_DSHOT_DMAR true + +#define PINIO1_PIN PC3 +#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 +// 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 + +#define USABLE_TIMER_CHANNEL_COUNT 12 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEEF405V3/target.mk b/src/main/target/SPEEDYBEEF405V3/target.mk new file mode 100644 index 0000000000..cb4965a77b --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/target.mk @@ -0,0 +1,19 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP SDCARD + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_bmi270.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ +drivers/barometer/barometer_bmp085.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/barometer/barometer_fake.c \ +drivers/barometer/barometer_lps.c \ +drivers/barometer/barometer_ms5611.c \ +drivers/barometer/barometer_qmp6988.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 1bce24c diff --git a/src/main/target/SPEEDYBEEF405V4/target.c b/src/main/target/SPEEDYBEEF405V4/target.c new file mode 100644 index 0000000000..7d23a6c998 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/target.c @@ -0,0 +1,47 @@ +/* + * 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: 34cc79d + +#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(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_ANY, 0, 0), // cam ctrl + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // ppm +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEEF405V4/target.h b/src/main/target/SPEEDYBEEF405V4/target.h new file mode 100644 index 0000000000..49363e53d9 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/target.h @@ -0,0 +1,150 @@ +/* + * 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: 34cc79d + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "SPBE" +#define USBD_PRODUCT_STRING "SPEEDYBEEF405V4" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID + +#define USE_ACC +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_SDCARD +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_SDCARD_SPI + +#define USE_VCP +#define USE_OSD + +#define USE_LED +#define LED0_PIN PC13 +#define LED_STRIP_PIN PA8 +#define USE_BEEPER +#define BEEPER_PIN PC15 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PB14 + +#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 PC2 +#define SPI2_MOSI_PIN PC3 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define GYRO_1_ALIGN CW90_DEG +#define ACC_1_ALIGN CW90_DEG +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PC4 + +#define ACC_ICM42688P_ALIGN CW90_DEG +#define GYRO_ICM42688P_ALIGN CW90_DEG +#define ICM42688P_CS_PIN PA4 +#define ICM42688P_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 PC10 +#define UART3_RX_PIN PC11 +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define SERIALRX_UART SERIAL_PORT_USART2 +#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 DASHBOARD_I2C_INSTANCE (I2CDEV_1) +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_SDCARD_SDIO +#define SDCARD_SPI_CS_PIN PC14 +#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 SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 +#define SDCARD_DETECT_INVERTED + +#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_INSTANCE SPI2 + +#define USE_ADC +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC5 +#define ADC1_DMA_OPT 0 +#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 400 + +#define ENABLE_DSHOT_DMAR false + +#define PINIO1_PIN PB11 +#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 +// 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 + +#define USABLE_TIMER_CHANNEL_COUNT 12 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) | TIM_N(12) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEEF405V4/target.mk b/src/main/target/SPEEDYBEEF405V4/target.mk new file mode 100644 index 0000000000..26842c6309 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/target.mk @@ -0,0 +1,19 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP SDCARD + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_icm426xx.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ +drivers/barometer/barometer_bmp085.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/barometer/barometer_fake.c \ +drivers/barometer/barometer_lps.c \ +drivers/barometer/barometer_ms5611.c \ +drivers/barometer/barometer_qmp6988.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 34cc79d diff --git a/src/main/target/SPEEDYBEEF7V3/target.c b/src/main/target/SPEEDYBEEF7V3/target.c new file mode 100644 index 0000000000..2e21c085f3 --- /dev/null +++ b/src/main/target/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/SPEEDYBEEF7V3/target.h b/src/main/target/SPEEDYBEEF7V3/target.h new file mode 100644 index 0000000000..8de845f81d --- /dev/null +++ b/src/main/target/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/SPEEDYBEEF7V3/target.mk b/src/main/target/SPEEDYBEEF7V3/target.mk new file mode 100644 index 0000000000..c97ce2f4ed --- /dev/null +++ b/src/main/target/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 + diff --git a/src/main/target/SPEEDYBEE_F745_AIO/target.c b/src/main/target/SPEEDYBEE_F745_AIO/target.c new file mode 100644 index 0000000000..342cc98739 --- /dev/null +++ b/src/main/target/SPEEDYBEE_F745_AIO/target.c @@ -0,0 +1,42 @@ +/* + * 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: 0808fa2 + +#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, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR, 0, 2), // motor 3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 1), // motor 4 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // ppm + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // led + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEE_F745_AIO/target.h b/src/main/target/SPEEDYBEE_F745_AIO/target.h new file mode 100644 index 0000000000..5f7d9f0eae --- /dev/null +++ b/src/main/target/SPEEDYBEE_F745_AIO/target.h @@ -0,0 +1,144 @@ +/* + * 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: 0808fa2 + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "SPBE" +#define USBD_PRODUCT_STRING "SPEEDYBEE_F745_AIO" + +#define FC_TARGET_MCU STM32F745 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S745" // generic ID + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_OSD + +#define USE_LED +#define LED0_PIN PA2 +#define LED_STRIP_PIN PD12 +#define USE_BEEPER +#define BEEPER_PIN PD15 +#define BEEPER_INVERTED +#define CAMERA_CONTROL_PIN PB3 + +#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_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_SPI_GYRO +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO_1_ALIGN CW90_DEG +#define ACC_1_ALIGN CW90_DEG +#define GYRO_1_CS_PIN PE4 +#define GYRO_1_EXTI_PIN PE1 +#define GYRO_1_SPI_INSTANCE SPI4 +#define MPU_INT_EXTI PE1 + +#define ACC_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG +#define MPU6000_CS_PIN PE4 +#define MPU6000_SPI_INSTANCE SPI4 + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define SERIAL_PORT_COUNT 6 + +#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 PB6 +#define I2C1_SDA PB7 + +#define FLASH_CS_PIN PA4 +#define FLASH_SPI_INSTANCE SPI1 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define MAX7456_SPI_CS_PIN PB12 +#define MAX7456_SPI_INSTANCE SPI2 + +#define USE_ADC +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define ADC1_DMA_OPT 0 +#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 256 + +#define ENABLE_DSHOT_DMAR true + +#define PINIO1_PIN PC4 +#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 TARGET_IO_PORTE 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 + +#define USABLE_TIMER_CHANNEL_COUNT 7 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/SPEEDYBEE_F745_AIO/target.mk b/src/main/target/SPEEDYBEE_F745_AIO/target.mk new file mode 100644 index 0000000000..324d360002 --- /dev/null +++ b/src/main/target/SPEEDYBEE_F745_AIO/target.mk @@ -0,0 +1,20 @@ +F7X5XG_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_mpu6000.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/pinio.c \ +drivers/max7456.c \ +drivers/barometer/barometer_bmp085.c \ +drivers/barometer/barometer_bmp280.c \ +drivers/barometer/barometer_fake.c \ +drivers/barometer/barometer_lps.c \ +drivers/barometer/barometer_ms5611.c \ +drivers/barometer/barometer_qmp6988.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: 4cb7ad1 diff --git a/src/main/target/STM32F7X2/config/CLRACINGF7.config b/src/main/target/STM32F7X2/config/CLRACINGF7.config deleted file mode 100644 index 2675de0d93..0000000000 --- a/src/main/target/STM32F7X2/config/CLRACINGF7.config +++ /dev/null @@ -1,89 +0,0 @@ -# Betaflight / STM32F745 (S745) 4.0.0 Mar 10 2019 / 21:49:53 (d6138c41e) MSP API: 1.41 - -board_name CLRACINGF7 -manufacturer_id CLRC - -# BEEPER -resource BEEPER 1 PB4 -set beeper_inversion = ON -set beeper_od = OFF - -# INDICATOR LED -resource LED 1 B00 - -#MOTOR AND LED -resource MOTOR 1 B06 -resource MOTOR 2 B07 -resource MOTOR 3 B08 -resource MOTOR 4 B09 -resource MOTOR 5 B01 -resource LED_STRIP 1 B01 - -# UARTS -resource SERIAL_TX 1 A09 -resource SERIAL_TX 2 A02 -resource SERIAL_TX 3 B10 -resource SERIAL_TX 4 A00 -resource SERIAL_TX 5 C12 -resource SERIAL_TX 6 C06 -resource SERIAL_RX 1 A10 -resource SERIAL_RX 2 A03 -resource SERIAL_RX 3 B11 -resource SERIAL_RX 4 A01 -resource SERIAL_RX 5 D02 -resource SERIAL_RX 6 C07 - -#SPI BUS -resource SPI_SCK 1 A05 -resource SPI_SCK 2 B13 -resource SPI_SCK 3 C10 -resource SPI_MISO 1 A06 -resource SPI_MISO 2 B14 -resource SPI_MISO 3 C11 -resource SPI_MOSI 1 A07 -resource SPI_MOSI 2 B15 -resource SPI_MOSI 3 B05 - -#ADC -resource ADC_BATT 1 C02 -resource ADC_RSSI 1 C03 -resource ADC_CURR 1 C01 -set current_meter = ADC -set battery_meter = ADC - -#SPI FLASH -resource FLASH_CS 1 B03 -set flash_spi_bus = 2 - -#OSD -resource OSD_CS 1 A15 -set max7456_spi_bus = 3 - -#GYRO -resource GYRO_EXTI 1 C04 -resource GYRO_CS 1 A04 -set gyro_1_bustype = SPI -set gyro_1_spibus = 1 -set gyro_1_sensor_align = CW0 - -# timer -timer B03 0 -timer B06 0 -timer B07 0 -timer B08 0 -timer B09 0 -timer B01 1 - -# dma -dma ADC 1 1 # ADC 1: DMA2 Stream 4 Channel 0 -dma pin B03 0 # pin B03: DMA1 Stream 6 Channel 3 -dma pin B06 0 # pin B06: DMA1 Stream 0 Channel 2 -dma pin B07 0 # pin B07: DMA1 Stream 3 Channel 2 -dma pin B08 0 # pin B08: DMA1 Stream 7 Channel 2 -dma pin B01 0 # pin B01: DMA1 Stream 2 Channel 5 - -# master -set system_hse_mhz = 8 -set dashboard_i2c_bus = 1 -resource RX_BIND_PLUG 1 B02 -resource CAMERA_CONTROL 1 B03 diff --git a/src/main/target/STM32F7X2/config/NERO.config b/src/main/target/STM32F7X2/config/NERO.config deleted file mode 100644 index 48672e785d..0000000000 --- a/src/main/target/STM32F7X2/config/NERO.config +++ /dev/null @@ -1,88 +0,0 @@ -# Usual lawyer stuff here? - -# Name: NERO -# Description: NERO Standard target configuration -# XXX We need something that remembers which config was loaded - -defaults nosave - -# Basic I/O -resource LED 1 B06 -resource LED 2 B05 -resource LED 3 B04 -resource beeper C1 -set beeper_inversion = ON -set beeper_od = OFF - -# Buses -resource I2C_SCL 1 B08 -resource I2C_SDA 1 B09 - -resource SPI_SCK 1 A05 -resource SPI_MISO 1 A06 -resource SPI_MOSI 1 A07 - -resource SPI_SCK 2 B13 -resource SPI_MISO 2 B14 -resource SPI_MOSI 2 B15 - -resource SPI_SCK 3 C10 -resource SPI_MISO 3 C11 -resource SPI_MOSI 3 C12 - -# SPI CS pins to pre-initialize -resource SPI_PREINIT_IPU 1 C04 // MPU6500 -resource SPI_PREINIT_IPU 2 A15 // SDCARD - -# Timers -# First four timers -# timer is zero origin -timer A0 1 -timer A1 1 -timer A2 1 -timer A3 1 -resource MOTOR 1 A0 -resource MOTOR 2 A1 -resource MOTOR 3 A2 -resource MOTOR 4 A3 - -# DMA stream conflict if burst mode is not used -# XXX Need a mechanism to specify dmaopt -set dshot_burst = ON - -# Remaining timers -timer B0 1 -timer B1 1 -timer C7 1 -timer C8 1 -timer C9 1 -resource LED_STRIP B0 -resource PPM C7 - -# Serial ports - -resource SERIAL_TX 1 A9 -resource SERIAL_RX 1 A10 - -resource SERIAL_TX 3 B10 -resource SERIAL_RX 3 B11 - -resource SERIAL_TX 6 C6 -resource SERIAL_RX 6 C7 - -# ADC - -resource ADC_BATT 1 C03 - -# Remaining - -resource ESCSERIAL 1 C07 -resource SDCARD_CS 1 A15 -resource SDCARD_DETECT 1 D02 - -# Some configs - -FEATURE RX_SERIAL -set serialrx_provider = SBUS -serial 5 64 115200 57600 0 115200 -set battery_meter = ADC diff --git a/src/main/target/HENA_TALONF7DJIHD/config.c b/src/main/target/TALONF7DJIHD/config.c similarity index 100% rename from src/main/target/HENA_TALONF7DJIHD/config.c rename to src/main/target/TALONF7DJIHD/config.c diff --git a/src/main/target/HENA_TALONF7DJIHD/target.c b/src/main/target/TALONF7DJIHD/target.c similarity index 100% rename from src/main/target/HENA_TALONF7DJIHD/target.c rename to src/main/target/TALONF7DJIHD/target.c diff --git a/src/main/target/HENA_TALONF7DJIHD/target.h b/src/main/target/TALONF7DJIHD/target.h similarity index 100% rename from src/main/target/HENA_TALONF7DJIHD/target.h rename to src/main/target/TALONF7DJIHD/target.h diff --git a/src/main/target/CRASHTESTF7/target.mk b/src/main/target/TALONF7DJIHD/target.mk similarity index 100% rename from src/main/target/CRASHTESTF7/target.mk rename to src/main/target/TALONF7DJIHD/target.mk diff --git a/src/main/target/TMTR_TMOTORF4/config.c b/src/main/target/TMOTORF4/config.c similarity index 100% rename from src/main/target/TMTR_TMOTORF4/config.c rename to src/main/target/TMOTORF4/config.c diff --git a/src/main/target/TMTR_TMOTORF4/target.c b/src/main/target/TMOTORF4/target.c similarity index 100% rename from src/main/target/TMTR_TMOTORF4/target.c rename to src/main/target/TMOTORF4/target.c diff --git a/src/main/target/TMTR_TMOTORF4/target.h b/src/main/target/TMOTORF4/target.h similarity index 100% rename from src/main/target/TMTR_TMOTORF4/target.h rename to src/main/target/TMOTORF4/target.h diff --git a/src/main/target/TMTR_TMOTORF4/target.mk b/src/main/target/TMOTORF4/target.mk similarity index 100% rename from src/main/target/TMTR_TMOTORF4/target.mk rename to src/main/target/TMOTORF4/target.mk diff --git a/src/main/target/TMTR_TMOTORF4HD/config.c b/src/main/target/TMOTORF4HD/config.c similarity index 100% rename from src/main/target/TMTR_TMOTORF4HD/config.c rename to src/main/target/TMOTORF4HD/config.c diff --git a/src/main/target/TMTR_TMOTORF4HD/target.c b/src/main/target/TMOTORF4HD/target.c similarity index 100% rename from src/main/target/TMTR_TMOTORF4HD/target.c rename to src/main/target/TMOTORF4HD/target.c diff --git a/src/main/target/TMTR_TMOTORF4HD/target.h b/src/main/target/TMOTORF4HD/target.h similarity index 100% rename from src/main/target/TMTR_TMOTORF4HD/target.h rename to src/main/target/TMOTORF4HD/target.h diff --git a/src/main/target/TMTR_TMOTORF4HD/target.mk b/src/main/target/TMOTORF4HD/target.mk similarity index 100% rename from src/main/target/TMTR_TMOTORF4HD/target.mk rename to src/main/target/TMOTORF4HD/target.mk diff --git a/src/main/target/TMOTORF7/target.c b/src/main/target/TMOTORF7/target.c new file mode 100644 index 0000000000..ecaa7704b1 --- /dev/null +++ b/src/main/target/TMOTORF7/target.c @@ -0,0 +1,40 @@ +/* + * 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 "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, 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(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/TMOTORF7/target.h similarity index 75% rename from src/main/target/TMTR_TMOTORF7/target.h rename to src/main/target/TMOTORF7/target.h index 1353cbead9..20ce09a1c2 100644 --- a/src/main/target/TMTR_TMOTORF7/target.h +++ b/src/main/target/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/TMOTORF7/target.mk similarity index 61% rename from src/main/target/TMTR_TMOTORF7/target.mk rename to src/main/target/TMOTORF7/target.mk index 15077cfbd3..c023c93328 100644 --- a/src/main/target/TMTR_TMOTORF7/target.mk +++ b/src/main/target/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 \ diff --git a/src/main/target/TMTR_TMPACERF7/target.c b/src/main/target/TMPACERF7/target.c similarity index 100% rename from src/main/target/TMTR_TMPACERF7/target.c rename to src/main/target/TMPACERF7/target.c diff --git a/src/main/target/TMTR_TMPACERF7/target.h b/src/main/target/TMPACERF7/target.h similarity index 100% rename from src/main/target/TMTR_TMPACERF7/target.h rename to src/main/target/TMPACERF7/target.h diff --git a/src/main/target/TMTR_TMPACERF7/target.mk b/src/main/target/TMPACERF7/target.mk similarity index 100% rename from src/main/target/TMTR_TMPACERF7/target.mk rename to src/main/target/TMPACERF7/target.mk diff --git a/src/main/target/TMTR_TMVELOX/config.c b/src/main/target/TMVELOX/config.c similarity index 100% rename from src/main/target/TMTR_TMVELOX/config.c rename to src/main/target/TMVELOX/config.c diff --git a/src/main/target/TMTR_TMVELOX/target.c b/src/main/target/TMVELOX/target.c similarity index 100% rename from src/main/target/TMTR_TMVELOX/target.c rename to src/main/target/TMVELOX/target.c diff --git a/src/main/target/TMTR_TMVELOX/target.h b/src/main/target/TMVELOX/target.h similarity index 100% rename from src/main/target/TMTR_TMVELOX/target.h rename to src/main/target/TMVELOX/target.h diff --git a/src/main/target/TMTR_TMVELOX/target.mk b/src/main/target/TMVELOX/target.mk similarity index 100% rename from src/main/target/TMTR_TMVELOX/target.mk rename to src/main/target/TMVELOX/target.mk diff --git a/src/main/target/TUNERCF405/target.c b/src/main/target/TUNERCF405/target.c new file mode 100644 index 0000000000..7621a11ebf --- /dev/null +++ b/src/main/target/TUNERCF405/target.c @@ -0,0 +1,44 @@ +/* + * 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: bacae61 + +#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, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 1 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // motor 2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // motor 3 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), // motor 4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 5 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 6 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 0, 0), // motor 7 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR, 0, 0), // motor 8 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // led +}; + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/TUNERCF405/target.h b/src/main/target/TUNERCF405/target.h new file mode 100644 index 0000000000..23595650b8 --- /dev/null +++ b/src/main/target/TUNERCF405/target.h @@ -0,0 +1,133 @@ +/* + * 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: bacae61 + +#pragma once + +#define TARGET_MANUFACTURER_IDENTIFIER "TURC" +#define USBD_PRODUCT_STRING "TUNERCF405" + +#define FC_TARGET_MCU STM32F405 // not used in EmuF +#define TARGET_BOARD_IDENTIFIER "S405" // generic ID + +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + +#define USE_VCP +#define USE_FLASHFS +#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c) +#define USE_OSD + +#define USE_LED +#define LED0_PIN PB9 +#define LED_STRIP_PIN PB1 +#define USE_BEEPER +#define BEEPER_PIN PB2 +#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 PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI +#define USE_GYRO_EXTI + +#define GYRO_1_ALIGN CW180_DEG +#define ACC_1_ALIGN CW180_DEG +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_EXTI_PIN PC4 +#define GYRO_1_SPI_INSTANCE SPI1 +#define MPU_INT_EXTI PC4 + +#define USE_SPI_GYRO +#define ACC_BMI270_ALIGN CW180_DEG +#define GYRO_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA4 +#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 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 USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C_DEVICE (I2CDEV_2) +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define FLASH_CS_PIN PB6 +#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_ADC +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define ADC1_DMA_OPT 0 +#define ADC3_DMA_OPT 1 +#define ADC1_DMA_STREAM DMA2_Stream0 //# ADC 1: DMA2 Stream 0 Channel 0 +#define ADC3_DMA_STREAM DMA2_Stream1 //# ADC 3: DMA2 Stream 1 Channel 2 +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC +#define DEFAULT_CURRENT_METER_SCALE 453 + +#define ENABLE_DSHOT_DMAR true + +#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 + +#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) + +// notice - this file was programmatically generated and may be incomplete. diff --git a/src/main/target/TUNERCF405/target.mk b/src/main/target/TUNERCF405/target.mk new file mode 100644 index 0000000000..088b5e5562 --- /dev/null +++ b/src/main/target/TUNERCF405/target.mk @@ -0,0 +1,12 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ +drivers/accgyro/accgyro_mpu.c \ +drivers/accgyro/accgyro_spi_bmi270.c \ +drivers/light_led.h \ +drivers/light_ws2811strip.c \ +drivers/max7456.c \ + +# This resource file generated using https://github.com/nerdCopter/target-convert +# Commit: bacae61 diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h index 2345ab8aba..1da8a2399c 100644 --- a/src/main/target/common_fc_pre.h +++ b/src/main/target/common_fc_pre.h @@ -170,6 +170,7 @@ #define MSP_OVER_CLI #define USE_OSD #define USE_OSD_OVER_MSP_DISPLAYPORT +#define USE_HDZERO_OSD #define USE_PINIO #define USE_PINIOBOX #define USE_RCDEVICE @@ -228,3 +229,6 @@ #define USE_CMS_FAILSAFE_MENU #define USE_CMS_GPS_RESCUE_MENU #endif + +// ICM42688P & BMI270 experimental define +#define USE_GYRO_DLPF_EXPERIMENTAL diff --git a/src/main/telemetry/ghst.c b/src/main/telemetry/ghst.c index b8dad14b4a..22b76681cb 100644 --- a/src/main/telemetry/ghst.c +++ b/src/main/telemetry/ghst.c @@ -82,9 +82,12 @@ static void ghstInitializeFrame(sbuf_t *dst) sbufWriteU8(dst, GHST_ADDR_RX); } +//compiler reports unused +/* STATIC_UNIT_TESTED uint8_t *getGhstFrame(){ return ghstFrame; } +*/ static void ghstFinalize(sbuf_t *dst) { diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index ab850449dc..42a38d7b80 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -66,10 +66,10 @@ #define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME #define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode" #define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode" -#define USBD_CONFIGURATION_HS_STRING "VCP Config" -#define USBD_INTERFACE_HS_STRING "VCP Interface" -#define USBD_CONFIGURATION_FS_STRING "VCP Config" -#define USBD_INTERFACE_FS_STRING "VCP Interface" +#define USBD_CONFIGURATION_HS_STRING "VCP Config in HS Mode" +#define USBD_INTERFACE_HS_STRING "VCP Interface in HS Mode" +#define USBD_CONFIGURATION_FS_STRING "VCP Config in FS Mode" +#define USBD_INTERFACE_FS_STRING "VCP Interface in FS Mode" /* Private macro -------------------------------------------------------------*/ /* Private function prototypes -----------------------------------------------*/ diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc index 5f1ca6571f..ffd3f6bf9f 100644 --- a/src/test/unit/rx_ibus_unittest.cc +++ b/src/test/unit/rx_ibus_unittest.cc @@ -90,7 +90,7 @@ static serialPortStub_t serialWriteStub; static bool portIsShared = false; bool isSerialPortShared(const serialPortConfig_t *portConfig, - uint16_t functionMask, + uint32_t functionMask, serialPortFunction_e sharedWithFunction) { EXPECT_EQ(portConfig, findSerialPortConfig_stub_retval); 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(); diff --git a/src/test/unit/telemetry_ibus_unittest.cc b/src/test/unit/telemetry_ibus_unittest.cc index e1c093b0c5..1637180768 100644 --- a/src/test/unit/telemetry_ibus_unittest.cc +++ b/src/test/unit/telemetry_ibus_unittest.cc @@ -185,7 +185,7 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing) bool isSerialPortShared(const serialPortConfig_t *portConfig, - uint16_t functionMask, + uint32_t functionMask, serialPortFunction_e sharedWithFunction) { EXPECT_EQ(findSerialPortConfig_stub_retval, portConfig);