Skip to content

Conversation

@jianpingwu1
Copy link
Contributor

@jianpingwu1 jianpingwu1 commented Jul 7, 2025

According to the suggestions in PR14510, split PR14510 into two separate PRs: ./lib update and ./src update, and resubmit them.

This submission adds support for the GD32F4 firmware library (./lib update).

Summary by CodeRabbit

  • New Features
    • Introduced comprehensive drivers and APIs for GD32F4xx microcontroller peripherals, including ADC, CAN, CRC, CTC, DAC, DBG, DCI, and core system configuration.
    • Added full support for initialization, configuration, control, data transfer, status monitoring, and interrupt management for each peripheral.
    • Provided detailed access to advanced features such as DMA, synchronization, calibration, watchdogs, power management, and debug options.
    • Enabled robust hardware abstraction for application development on GD32F4xx devices.

@github-actions
Copy link

github-actions bot commented Jul 7, 2025

Do you want to test this code? You can flash it directly from Betaflight Configurator:

  • Simply put #14519 (this pull request number) in the Select commit field of the Configurator firmware flasher tab (you need to Enable expert mode, Show release candidates and Development).

WARNING: It may be unstable. Use only for testing!

@coderabbitai
Copy link
Contributor

coderabbitai bot commented Jul 7, 2025

Important

Review skipped

Review was skipped as selected files did not have any reviewable changes.

💤 Files selected but had no reviewable changes (1)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_timer.c

You can disable this status message by setting the reviews.review_status to false in the CodeRabbit configuration file.

Walkthrough

This change introduces a comprehensive set of CMSIS and standard peripheral driver headers and source files for the GD32F4xx microcontroller series. It adds device-specific definitions, register mappings, macros, data structures, and a full suite of driver APIs for all core peripherals, including ADC, CAN, CRC, CTC, DAC, DBG, DCI, DMA, EXMC, EXTI, FMC, FWDGT, GPIO, I2C, IPA, IREF, MISC, PMU, RCU, RTC, SDIO, SPI, SYSCFG, TIMER, TLI, TRNG, USART, and WWDGT. Each peripheral is provided with both header and source files implementing initialization, configuration, control, data transfer, interrupt, and flag management functions.

Changes

Files Change Summary
.../CMSIS/GD/GD32F4xx/Include/gd32f4xx.h, system_gd32f4xx.h Added core device and system headers with register/memory definitions, IRQn, enums, and system clock API.
.../CMSIS/GD/GD32F4xx/Source/system_gd32f4xx.c Added system initialization and clock configuration source with SystemInit, SystemCoreClockUpdate, and related logic.
.../GD32F4xx_standard_peripheral/Include/gd32f4xx_*.h Added headers for all standard peripherals (ADC, CAN, CRC, CTC, DAC, DBG, DCI, DMA, EXMC, EXTI, FMC, FWDGT, GPIO, I2C, IPA, IREF, MISC, PMU, RCU, RTC, SDIO, SPI, SYSCFG, TIMER, TLI, TRNG, USART, WWDGT) with register definitions, macros, data structures, and function prototypes.
.../GD32F4xx_standard_peripheral/Source/gd32f4xx_*.c Added source files implementing full driver logic for ADC, CAN, CRC, CTC, DAC, DBG, DCI, with functions for peripheral initialization, configuration, data transfer, interrupt, and flag handling.

Sequence Diagram(s)

sequenceDiagram
    participant UserApp
    participant PeripheralDriver
    participant HW_Registers

    UserApp->>PeripheralDriver: Initialize Peripheral (e.g., ADC, CAN, etc.)
    PeripheralDriver->>HW_Registers: Write configuration registers
    HW_Registers-->>PeripheralDriver: Registers updated
    UserApp->>PeripheralDriver: Start operation (e.g., start conversion, transmit)
    PeripheralDriver->>HW_Registers: Set control bits
    HW_Registers-->>PeripheralDriver: Operation proceeds
    HW_Registers-->>PeripheralDriver: Interrupt/Flag set
    PeripheralDriver->>UserApp: Notify via flag/interrupt handler
    UserApp->>PeripheralDriver: Read data/status
    PeripheralDriver->>HW_Registers: Read data/status registers
    HW_Registers-->>PeripheralDriver: Return data/status
    PeripheralDriver-->>UserApp: Return data/status
Loading
sequenceDiagram
    participant System
    participant SystemInit
    participant RCU
    participant HW_Registers

    System->>SystemInit: Power-on or Reset
    SystemInit->>RCU: Configure clock source/frequency
    RCU->>HW_Registers: Set oscillator, PLL, prescaler registers
    HW_Registers-->>RCU: Oscillator/PLL stabilization
    RCU-->>SystemInit: Clock ready
    SystemInit->>System: SystemCoreClock updated
Loading
✨ Finishing touches
🧪 Generate unit tests (beta)
  • Create PR with unit tests
  • Post copyable unit tests in a comment

Thanks for using CodeRabbit! It's free for OSS, and your support helps us grow. If you like it, consider giving us a shout-out.

❤️ Share

Comment @coderabbitai help to get the list of available commands and usage tips.

Copy link
Contributor

@coderabbitai coderabbitai bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actionable comments posted: 35

🧹 Nitpick comments (39)
lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Include/system_gd32f4xx.h (2)

45-47: Macro is defined although the comment says it should be “uncommented”

The line declares #define __FIRMWARE_VERSION_DEFINE, but the preceding comment implies it should be disabled by default and enabled only when a version‐getter is required. Shipping the header with the macro enabled forces every translation unit that includes this header to expect gd32f4xx_firmware_version_get() to be available, leading to a link error if the symbol is not compiled in.

-/* firmware version can be aquired by uncommenting the macro */
-#define __FIRMWARE_VERSION_DEFINE
+/* Uncomment to expose gd32f4xx_firmware_version_get() */
+/* #define __FIRMWARE_VERSION_DEFINE */

56-59: Typo in comment (“aquired”)

aquiredacquired. Tiny but shows up in all IDE tooltips.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_crc.h (1)

74-76: Parameter const-correctness & size type

CRC functions never mutate the input buffer, yet array is declared mutable and the length is a 32-bit word count instead of a generic size type.

-uint32_t crc_block_data_calculate(uint32_t array[], uint32_t size);
+uint32_t crc_block_data_calculate(const uint32_t *array, size_t length);

Using const enables the compiler to place the buffer in ROM and prevents accidental writes; size_t removes the 4 GiB limitation when the code is eventually compiled on 64-bit hosts.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_iref.h (1)

55-73: Explosion of one-line macros clutters the public API

Sixty-four separate IREF_CUR_PRECISION_TRIM_x macros (and another 64 for step data) massively inflate the global namespace and slow down IntelliSense. A single parametrised helper already exists (CTL_CPT() / CTL_CSDT()); publishing all enumerations is unnecessary.

Consider trimming the header to:

/* helper macros – keep */
#define CTL_CPT(val)  (BITS(8,12) & ((uint32_t)(val) << 8))
#define CTL_CSDT(val) (BITS(0,5) & ((uint32_t)(val) << 0))

/* typical usage examples – remove the huge enum list */
#define IREF_CUR_PRECISION_TRIM(n)  CTL_CPT(n)   /* n = 0-31 */
#define IREF_CUR_STEP_DATA(n)       CTL_CSDT(n)  /* n = 0-63 */

Clients then pass the numeric value directly, keeping the header compact.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_trng.h (1)

71-75: Spelling: “inerrupt” → “interrupt”

Minor typo in the comment block heading; fixes grep-ability.

-/* TRNG inerrupt flag */
+/* TRNG interrupt flag */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_wwdgt.h (1)

62-67: Prefer an enum for prescaler values

The prescaler constants belong to the same conceptual set; using an enum clarifies intent and gives type safety:

-#define WWDGT_CFG_PSC_DIV1  CFG_PSC(0)
-#define WWDGT_CFG_PSC_DIV2  CFG_PSC(1)
-#define WWDGT_CFG_PSC_DIV4  CFG_PSC(2)
-#define WWDGT_CFG_PSC_DIV8  CFG_PSC(3)
+typedef enum {
+    WWDGT_PSC_DIV1 = CFG_PSC(0),
+    WWDGT_PSC_DIV2 = CFG_PSC(1),
+    WWDGT_PSC_DIV4 = CFG_PSC(2),
+    WWDGT_PSC_DIV8 = CFG_PSC(3)
+} wwdgt_prescaler_t;

Update the API to accept wwdgt_prescaler_t instead of raw uint32_t.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_crc.c (1)

37-39: Consider using designated initializers for magic values.

The magic constants would benefit from more descriptive names and could be defined in the header file for better maintainability.

Consider moving these to the header file:

+/* in gd32f4xx_crc.h */
+#define CRC_DATA_RESET_VALUE      ((uint32_t)0xFFFFFFFFU)  /*!< CRC data register reset value */
+#define CRC_FDATA_RESET_VALUE     ((uint32_t)0x00000000U)  /*!< CRC free data register reset value */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dbg.h (2)

63-64: Use consistent capitalization for "MCU" in comments.

For consistency with other comments in the codebase, "mcu" should be capitalized as "MCU".

-    \brief    enable low power behavior when the mcu is in debug mode
+    \brief    enable low power behavior when the MCU is in debug mode
-    \brief    disable low power behavior when the mcu is in debug mode
+    \brief    disable low power behavior when the MCU is in debug mode

Also applies to: 78-79


127-127: Add space after closing brace in typedef.

Add a space between the closing brace and the typedef name for better readability.

-}dbg_periph_enum;
+} dbg_periph_enum;
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dbg.c (1)

63-64: Use consistent capitalization for "MCU" in comments.

For consistency with other comments in the codebase, "mcu" should be capitalized as "MCU".

-    \brief    enable low power behavior when the mcu is in debug mode
+    \brief    enable low power behavior when the MCU is in debug mode
-    \brief    disable low power behavior when the mcu is in debug mode
+    \brief    disable low power behavior when the MCU is in debug mode
-    \brief    enable peripheral behavior when the mcu is in debug mode
+    \brief    enable peripheral behavior when the MCU is in debug mode
-    \brief    disable peripheral behavior when the mcu is in debug mode
+    \brief    disable peripheral behavior when the MCU is in debug mode

Also applies to: 78-79, 93-94, 126-127

lib/main/GD32F4/Drivers/CMSIS/core_cmInstr.h (1)

406-413: Fix duplicate parameter names in __ROR documentation.

The documentation has duplicate parameter names. The second parameter should describe the rotation amount.

     \param [in]    value  Value to rotate
-    \param [in]    value  Number of Bits to rotate
+    \param [in]    shift  Number of bits to rotate
     \return               Rotated value
 */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_gpio.h (2)

284-284: Consider removing the redundant type alias.

The bit_status type alias for FlagStatus appears unnecessary and inconsistent with the naming conventions used elsewhere in the file. The function declarations already use both types interchangeably (e.g., gpio_bit_write uses bit_status while gpio_input_bit_get returns FlagStatus).

Consider using FlagStatus directly throughout the file for consistency:

-typedef FlagStatus bit_status;

And update the function declaration:

-void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, bit_status bit_value);
+void gpio_bit_write(uint32_t gpio_periph, uint32_t pin, FlagStatus bit_value);

67-67: Remove trailing spaces.

Several lines have trailing spaces that should be removed for consistency.

Also applies to: 350-350, 352-352

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_ctc.h (1)

51-51: Remove trailing space.

lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Source/system_gd32f4xx.c (2)

297-299: Clarify the wait condition comment.

The comment "wait until IRC16M is selected as system clock" is misleading. The code is actually waiting for the system clock source status to confirm IRC16M selection after line 295 sets it.

Update the comment to be more accurate:

-    /* wait until IRC16M is selected as system clock */
+    /* wait until system clock source status confirms IRC16M */

650-652: Minor inconsistency in timeout handling pattern.

This function uses inline increment in the while condition, whereas other similar functions use do-while loops with separate increment statements. While functionally equivalent, consider using a consistent pattern throughout the file.

lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Include/gd32f4xx.h (2)

90-92: Document why I2S_EXTERNAL_CLOCK_IN is commented out.

The I2S external clock definition is commented out without explanation. Consider adding a comment explaining why this is disabled by default or remove it if it's not needed.

 /* I2S external clock in selection */
-//#define I2S_EXTERNAL_CLOCK_IN          (uint32_t)12288000U
+/* I2S_EXTERNAL_CLOCK_IN can be defined by the user if an external I2S clock is used */
+/* #define I2S_EXTERNAL_CLOCK_IN          (uint32_t)12288000U */

303-305: Remove commented code or explain its purpose.

Line 304 contains commented code that appears to be an alternative BIT macro implementation. Either remove it or explain why it's kept as a comment.

 #ifndef BIT
 #define BIT(x)                       ((uint32_t)((uint32_t)0x01U<<(x)))
-// #define BIT(x) ((uint32_t)(1 << (x)))
 #endif
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dci.c (1)

63-77: Consider adding parameter validation.

The dci_init function doesn't validate the input parameter. Consider adding a NULL check for defensive programming.

 void dci_init(dci_parameter_struct *dci_struct)
 {
+    /* check the parameters */
+    if(NULL == dci_struct) {
+        return;
+    }
+    
     uint32_t reg = 0U;
     /* disable capture function and DCI */
     DCI_CTL &= ~(DCI_CTL_CAP | DCI_CTL_DCIEN);
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dac.c (2)

443-449: Remove unnecessary local variable

The local variable ctl is used only once and can be inlined for better readability.

 void dac_concurrent_enable(uint32_t dac_periph)
 {
-    uint32_t ctl = 0U;
-
-    ctl = (uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1);
-    DAC_CTL0(dac_periph) |= (uint32_t)ctl;
+    DAC_CTL0(dac_periph) |= (uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1);
 }
 void dac_concurrent_disable(uint32_t dac_periph)  
 {
-    uint32_t ctl = 0U;
-
-    ctl = (uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1);
-    DAC_CTL0(dac_periph) &= (uint32_t)(~ctl);
+    DAC_CTL0(dac_periph) &= ~(uint32_t)(DAC_CTL0_DEN0 | DAC_CTL0_DEN1);
 }

Also applies to: 457-463


476-476: Remove trailing whitespace

-    DAC_SWT(dac_periph) |= (uint32_t)swt; 
+    DAC_SWT(dac_periph) |= (uint32_t)swt;
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_can.c (3)

113-113: Fix inconsistent literal suffix

-        ((can_trasnmit_message_struct *)p_struct)->tx_dlen = 0u;
+        ((can_trasnmit_message_struct *)p_struct)->tx_dlen = 0U;

595-602: Improve code formatting consistency

The spacing in these assignments is inconsistent with the rest of the code.

-    receive_message -> rx_data[0] = (uint8_t)(GET_RFIFOMDATA0_DB0(CAN_RFIFOMDATA0(can_periph, fifo_number)));
-    receive_message -> rx_data[1] = (uint8_t)(GET_RFIFOMDATA0_DB1(CAN_RFIFOMDATA0(can_periph, fifo_number)));
+    receive_message->rx_data[0] = (uint8_t)(GET_RFIFOMDATA0_DB0(CAN_RFIFOMDATA0(can_periph, fifo_number)));
+    receive_message->rx_data[1] = (uint8_t)(GET_RFIFOMDATA0_DB1(CAN_RFIFOMDATA0(can_periph, fifo_number)));

Apply this change to all similar lines.


739-739: Use consistent hex notation

-    while((0U != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) && (0x00U != timeout)) {
+    while((0U != (CAN_STAT(can_periph) & CAN_STAT_SLPWS)) && (0U != timeout)) {
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_can.h (1)

467-467: Fix typo in comment.

-    CAN_INIT_STRUCT = 0,                                                /* CAN initiliaze parameters struct */
+    CAN_INIT_STRUCT = 0,                                                /* CAN initialize parameters struct */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_spi.h (1)

140-140: Fix typo in comment.

-/* SPI_SPI_QCTL(only SPI5) */
+/* SPI_QCTL(only SPI5) */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_rcu.h (3)

160-160: Remove trailing whitespace

There's trailing whitespace at the end of this line.

-#define RCU_AHB2RST_USBFSRST            BIT(7)                    /*!< USBFS reset */
+#define RCU_AHB2RST_USBFSRST            BIT(7)                    /*!< USBFS reset */

387-392: Use proper multi-line comment syntax

The multi-line comment should use proper /* */ syntax for better readability.

-#define RCU_PLLSSCTL_MODCNT             BITS(0,12)                /*!< these bits configure PLL spread spectrum modulation 
-                                                                       profile amplitude and frequency. the following criteria 
-                                                                       must be met: MODSTEP*MODCNT=215-1 */
-#define RCU_PLLSSCTL_MODSTEP            BITS(13,27)               /*!< these bits configure PLL spread spectrum modulation 
-                                                                       profile amplitude and frequency. the following criteria 
-                                                                       must be met: MODSTEP*MODCNT=215-1 */
+#define RCU_PLLSSCTL_MODCNT             BITS(0,12)                /*!< these bits configure PLL spread spectrum modulation 
+                                                                       profile amplitude and frequency. the following criteria 
+                                                                       must be met: MODSTEP*MODCNT=2^15-1 */
+#define RCU_PLLSSCTL_MODSTEP            BITS(13,27)               /*!< these bits configure PLL spread spectrum modulation 
+                                                                       profile amplitude and frequency. the following criteria 
+                                                                       must be met: MODSTEP*MODCNT=2^15-1 */

Also note that "215-1" should likely be "2^15-1" to clarify it's 2 to the power of 15 minus 1.


528-528: Remove trailing whitespace

Remove trailing spaces from these lines.

-    RCU_TIMER13   = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 8U),                  /*!< TIMER13 clock */   
+    RCU_TIMER13   = RCU_REGIDX_BIT(APB1EN_REG_OFFSET, 8U),                  /*!< TIMER13 clock */
-    RCU_TIMER13_SLP   = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 8U),            /*!< TIMER13 clock */   
+    RCU_TIMER13_SLP   = RCU_REGIDX_BIT(APB1SPEN_REG_OFFSET, 8U),            /*!< TIMER13 clock */
-    RCU_TIMER13RST   = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 8U),              /*!< TIMER13 clock reset */   
+    RCU_TIMER13RST   = RCU_REGIDX_BIT(APB1RST_REG_OFFSET, 8U),              /*!< TIMER13 clock reset */

Also applies to: 613-613, 687-687

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_i2c.h (1)

91-91: Fix typo in comment

"aual-address" should be "dual-address".

-#define I2C_SADDR1_DUADEN             BIT(0)                            /*!< aual-address mode switch */
+#define I2C_SADDR1_DUADEN             BIT(0)                            /*!< dual-address mode switch */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dma.h (1)

39-39: Add missing space in C++ extern closing comment.

For consistency with standard formatting practices, add a space before the comment text.

-#endif /* __cplusplus */   
+#endif /* __cplusplus */
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_exmc.h (3)

438-443: Use consistent comment style: /*!< */ instead of /* */.

For consistency with the rest of the file, use the doxygen-style inline comments.

-#define EXMC_ECC_SIZE_256BYTES              NPCTL_ECCSZ(0)                /* ECC size is 256 bytes */
-#define EXMC_ECC_SIZE_512BYTES              NPCTL_ECCSZ(1)                /* ECC size is 512 bytes */
-#define EXMC_ECC_SIZE_1024BYTES             NPCTL_ECCSZ(2)                /* ECC size is 1024 bytes */
-#define EXMC_ECC_SIZE_2048BYTES             NPCTL_ECCSZ(3)                /* ECC size is 2048 bytes */
-#define EXMC_ECC_SIZE_4096BYTES             NPCTL_ECCSZ(4)                /* ECC size is 4096 bytes */
-#define EXMC_ECC_SIZE_8192BYTES             NPCTL_ECCSZ(5)                /* ECC size is 8192 bytes */
+#define EXMC_ECC_SIZE_256BYTES              NPCTL_ECCSZ(0)                /*!< ECC size is 256 bytes */
+#define EXMC_ECC_SIZE_512BYTES              NPCTL_ECCSZ(1)                /*!< ECC size is 512 bytes */
+#define EXMC_ECC_SIZE_1024BYTES             NPCTL_ECCSZ(2)                /*!< ECC size is 1024 bytes */
+#define EXMC_ECC_SIZE_2048BYTES             NPCTL_ECCSZ(3)                /*!< ECC size is 2048 bytes */
+#define EXMC_ECC_SIZE_4096BYTES             NPCTL_ECCSZ(4)                /*!< ECC size is 4096 bytes */
+#define EXMC_ECC_SIZE_8192BYTES             NPCTL_ECCSZ(5)                /*!< ECC size is 8192 bytes */

447-462: Use consistent comment style: /*!< */ instead of /* */.

For consistency with the rest of the file, use the doxygen-style inline comments.

-#define EXMC_ALE_RE_DELAY_1_HCLK            NPCTL_ATR(0)                  /* ALE to RE delay = 1*HCLK */
-#define EXMC_ALE_RE_DELAY_2_HCLK            NPCTL_ATR(1)                  /* ALE to RE delay = 2*HCLK */
+#define EXMC_ALE_RE_DELAY_1_HCLK            NPCTL_ATR(0)                  /*!< ALE to RE delay = 1*HCLK */
+#define EXMC_ALE_RE_DELAY_2_HCLK            NPCTL_ATR(1)                  /*!< ALE to RE delay = 2*HCLK */

Apply this pattern to all 16 lines in this section.


466-481: Use consistent comment style: /*!< */ instead of /* */.

For consistency with the rest of the file, use the doxygen-style inline comments.

-#define EXMC_CLE_RE_DELAY_1_HCLK            NPCTL_CTR(0)                  /* CLE to RE delay = 1*HCLK */
-#define EXMC_CLE_RE_DELAY_2_HCLK            NPCTL_CTR(1)                  /* CLE to RE delay = 2*HCLK */
+#define EXMC_CLE_RE_DELAY_1_HCLK            NPCTL_CTR(0)                  /*!< CLE to RE delay = 1*HCLK */
+#define EXMC_CLE_RE_DELAY_2_HCLK            NPCTL_CTR(1)                  /*!< CLE to RE delay = 2*HCLK */

Apply this pattern to all 16 lines in this section.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_timer.h (3)

518-518: Fix comment formatting for consistency

Remove extra spaces in the comment.

-#define TIMER_UPDATECTL_CCUTRI              ((uint32_t)0x00000001U)                        /*!< the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs */
+#define TIMER_UPDATECTL_CCUTRI              ((uint32_t)0x00000001U)                 /*!< the shadow registers update by when CMTG bit is set or an rising edge of TRGI occurs */

487-488: Add 'U' suffix for consistency with other unsigned constants

These constants should have the 'U' suffix like other similar definitions in the file.

-#define TIMER_OC_IDLE_STATE_HIGH            ((uint16_t)0x0100)                      /*!< idle state of channel output is high */
-#define TIMER_OC_IDLE_STATE_LOW             ((uint16_t)0x0000)                      /*!< idle state of channel output is low */
+#define TIMER_OC_IDLE_STATE_HIGH            ((uint16_t)0x0100U)                     /*!< idle state of channel output is high */
+#define TIMER_OC_IDLE_STATE_LOW             ((uint16_t)0x0000U)                     /*!< idle state of channel output is low */

776-777: Remove extra blank line at end of file

 #endif /* GD32F4XX_TIMER_H */
-
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_adc.h (2)

413-413: Remove spaces before commas in function parameters.

The function declarations have non-standard spacing before commas. This should be fixed for consistency with typical C style guidelines.

For example, change:

-void adc_special_function_config(uint32_t adc_periph , uint32_t function , ControlStatus newvalue);
+void adc_special_function_config(uint32_t adc_periph, uint32_t function, ControlStatus newvalue);

Apply this change to all function declarations in the file.

Also applies to: 445-445, 447-451, 453-461


513-514: Add newline at end of file.

The file should end with a newline character to avoid potential compilation warnings.

Ensure the file ends with a newline after the #endif directive.

📜 Review details

Configuration used: .coderabbit.yaml
Review profile: CHILL
Plan: Pro

📥 Commits

Reviewing files that changed from the base of the PR and between b6d3700 and 10654da.

📒 Files selected for processing (41)
  • lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Include/gd32f4xx.h (1 hunks)
  • lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Include/system_gd32f4xx.h (1 hunks)
  • lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Source/system_gd32f4xx.c (1 hunks)
  • lib/main/GD32F4/Drivers/CMSIS/core_cm4_simd.h (1 hunks)
  • lib/main/GD32F4/Drivers/CMSIS/core_cmFunc.h (1 hunks)
  • lib/main/GD32F4/Drivers/CMSIS/core_cmInstr.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_adc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_can.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_crc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_ctc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dac.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dbg.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dci.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dma.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_exmc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_exti.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_fmc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_fwdgt.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_gpio.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_i2c.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_ipa.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_iref.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_misc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_pmu.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_rcu.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_rtc.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_sdio.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_spi.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_syscfg.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_timer.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_tli.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_trng.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_usart.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_wwdgt.h (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_adc.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_can.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_crc.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_ctc.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dac.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dbg.c (1 hunks)
  • lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dci.c (1 hunks)
🧰 Additional context used
🧠 Learnings (4)
📓 Common learnings
Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: PR #14378 increases the PINIO limit from 4 to 8 to support flight controllers that use analog switches driven by GPIOs, requiring more configurable pins.
Learnt from: blckmn
PR: betaflight/betaflight#14437
File: src/main/build/build_config.h:66-66
Timestamp: 2025-06-09T09:15:59.886Z
Learning: RP2350 MCU support in Betaflight is being added incrementally, with the enum definitions for MCU_TYPE_RP2350A and MCU_TYPE_RP2350B added first in build_config.h, while platform implementation may be in a separate branch or coming in subsequent commits.
Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: In Betaflight PR #14378, increasing the PINIO limit from 4 to 8 required only changing the PINIO_COUNT macro definition in src/main/drivers/pinio.h, as all array sizes and loops throughout the codebase reference this constant.
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_gpio.h (2)
Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: In Betaflight PR #14378, increasing the PINIO limit from 4 to 8 required only changing the PINIO_COUNT macro definition in src/main/drivers/pinio.h, as all array sizes and loops throughout the codebase reference this constant.
Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: PR #14378 increases the PINIO limit from 4 to 8 to support flight controllers that use analog switches driven by GPIOs, requiring more configurable pins.
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_spi.h (1)
Learnt from: cvetaevvitaliy
PR: betaflight/betaflight#14348
File: src/main/drivers/accgyro/accgyro_spi_icm456xx.c:50-60
Timestamp: 2025-05-02T18:40:24.331Z
Learning: When implementing SPI read functions in Betaflight, provide implementations for both DMA and non-DMA modes, using spiReadRegMskBufRB for the non-DMA case.
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dma.h (1)
Learnt from: blckmn
PR: betaflight/betaflight#14471
File: src/main/cli/cli.c:5409-5411
Timestamp: 2025-06-22T11:57:06.000Z
Learning: DMA_STCH_STRING fallback in src/main/cli/cli.c should be "Channel" not "Stream" because modern STM32 variants (F4/F7/H7) and APM32F4 explicitly define it as "Stream" in their platform headers, while the fallback "Channel" is for simpler platforms that only have DMA channels without the stream concept.
🔇 Additional comments (33)
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_misc.h (1)

1-91: LGTM! Well-structured NVIC and system control interface.

The header file provides a comprehensive and properly structured interface for NVIC configuration, system low power management, and SysTick control. The constants, bit definitions, and function declarations follow CMSIS conventions and appear correct for the GD32F4xx microcontroller series.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_syscfg.h (1)

1-179: LGTM! Comprehensive system configuration interface.

The SYSCFG header provides a well-organized interface for system-level configuration including boot modes, memory mapping, EXTI line routing, and Ethernet PHY selection. The register definitions, bit fields, and constants are properly structured and the EXTI source mappings comprehensively cover all GPIO ports and pins.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_fwdgt.h (1)

1-111: LGTM! Proper watchdog timer interface with security considerations.

The FWDGT header provides a complete interface for the Free Watchdog Timer with appropriate security measures. The prescaler range (DIV4 to DIV256), control keys (0x5555, 0xAAAA, 0xCCCC), and timeout values follow standard watchdog implementation patterns. The function declarations cover all necessary watchdog operations including configuration, enable/disable, and status monitoring.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_exti.h (1)

230-241: Fix missing enum value in exti_mode_enum.

The EXTI_EVENT enum value is missing its explicit value assignment, which could lead to unexpected behavior.

 typedef enum {
     EXTI_INTERRUPT   = 0,                                     /*!< EXTI interrupt mode */
-    EXTI_EVENT                                                /*!< EXTI event mode */
+    EXTI_EVENT       = 1                                      /*!< EXTI event mode */
 } exti_mode_enum;

Likely an incorrect or invalid review comment.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_pmu.h (1)

1-204: LGTM!

The PMU header file is well-structured with consistent naming conventions, proper documentation, and clear macro definitions.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_gpio.h (1)

41-406: Well-structured GPIO driver header.

The GPIO peripheral definitions follow standard patterns with:

  • Consistent register offset definitions
  • Properly parenthesized macros
  • Comprehensive bit field definitions
  • Complete API coverage for GPIO operations
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_ctc.h (1)

35-182: Well-implemented CTC peripheral header.

The Clock Trim Controller header provides:

  • Clear register and bit field definitions
  • Comprehensive symbolic constants for configuration
  • Complete API for CTC operations
  • Proper separation of interrupt flags and control bits
lib/main/GD32F4/Drivers/CMSIS/core_cm4_simd.h (1)

50-697: Standard CMSIS SIMD implementation.

The file provides comprehensive SIMD intrinsic support for:

  • Multiple compilers (ARM, GCC, IAR, TI, TASKING, COSMIC)
  • All Cortex-M4 SIMD instructions
  • Proper inline assembly implementations
lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Source/system_gd32f4xx.c (2)

66-107: Voltage stabilization mechanism acknowledged.

The RCU_MODIFY_4 macro implements a gradual clock division strategy to prevent core voltage fluctuations during frequency switching. This is a critical safety mechanism for the GD32F4xx series.


176-1266: Comprehensive system clock configuration.

The system initialization provides:

  • Multiple clock source options (IRC16M, HXTAL, PLL)
  • Proper oscillator startup verification
  • Power management for high-frequency operation
  • Safe frequency switching with voltage protection
lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_ctc.c (1)

51-388: Well-implemented CTC driver.

The driver provides:

  • Complete implementation of all CTC functions
  • Consistent bit manipulation patterns
  • Proper flag and interrupt handling
  • Clear separation of read/write operations
lib/main/GD32F4/Drivers/CMSIS/GD/GD32F4xx/Include/gd32f4xx.h (1)

171-213: Well-structured conditional IRQ definitions.

The interrupt definitions are properly organized with conditional compilation based on chip variants (GD32F450/460/470, GD32F405/425, GD32F407/427). This ensures only relevant interrupts are defined for each variant.

Also applies to: 215-246, 248-282

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dci.h (2)

124-134: Well-designed parameter structure.

The dci_parameter_struct is well-organized with clear member names and appropriate data types for DCI configuration.


193-194: Fix typo in function comment.

There's a typo in the comment: "disble" should be "disable".

-    \brief    disble embedded synchronous mode
+    \brief    disable embedded synchronous mode

Likely an incorrect or invalid review comment.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_dci.c (1)

256-273: Efficient flag status checking implementation.

The dci_flag_get function cleverly uses bit 31 to determine which status register to read, avoiding the need for a large switch statement. This is an elegant solution.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_dac.h (2)

124-183: Comprehensive DAC configuration constants.

The DAC configuration constants are well-organized with clear definitions for:

  • Trigger sources (TIMER, EXTI, software)
  • Wave modes (LFSR noise, triangle)
  • Multiple bit width options
  • Clear amplitude settings

This provides excellent flexibility for DAC configuration.


249-262: Good support for concurrent DAC operation.

The concurrent mode functions allow synchronized operation of both DAC channels, which is useful for applications requiring coordinated analog outputs.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_sdio.h (3)

178-256: Excellent flag and interrupt definitions.

The SDIO flags and interrupts are comprehensively defined with clear naming conventions. The separation between flags, interrupts, and interrupt flags provides good clarity for different use cases.


397-430: Comprehensive SD I/O and CE-ATA support.

The inclusion of specialized functions for SD I/O mode (read wait, suspend) and CE-ATA commands demonstrates thorough peripheral support. This enables full utilization of advanced SDIO features.


257-325: Well-designed configuration constants.

The configuration constants use macros effectively to create readable and type-safe definitions for:

  • Power control states
  • Bus modes (1-bit, 4-bit, 8-bit)
  • Clock edge selection
  • Data block sizes (1 byte to 16KB)

This design pattern makes the API easy to use and reduces errors.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_fmc.h (2)

111-112: Verify bit field definitions for potential overlap

FMC_PE_ADDR is defined as BITS(0,28) while FMC_PE_EN is BIT(31). Please verify that bits 29-30 are intentionally unused.


277-292: Non-sequential sector numbering may cause confusion

The sector numbering jumps from 11 to 24, then back to 12. This non-sequential ordering could lead to confusion when using these constants.

Please verify if this ordering matches the hardware specification. If so, consider adding a comment explaining the non-sequential numbering.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_ipa.h (1)

1-378: Well-structured header file

The IPA header file is well-organized with comprehensive register definitions, bit masks, data structures, and function declarations. The code follows consistent naming conventions and provides clear documentation.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_rcu.h (1)

1-1181: Well-structured RCU header implementation

This is a comprehensive and well-organized header file for the GD32F4xx Reset and Clock Control Unit. The register definitions, bit masks, and function declarations follow standard microcontroller firmware patterns. Only minor formatting issues were found.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_i2c.h (1)

1-410: Well-implemented I2C peripheral header

This is a comprehensive I2C peripheral driver header that provides complete register definitions, bit masks, and a full API for I2C operations including SMBus support, DMA mode, noise filtering, and SAM interface control. The code follows consistent patterns and is well-documented. Only one minor typo was found.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_timer.h (2)

1-777: Well-structured timer peripheral driver implementation

This is a comprehensive and well-organized timer peripheral driver header that provides complete support for the GD32F4xx timer peripherals. The code follows consistent naming conventions and provides clear documentation through comments.

The implementation correctly handles the differences between 16-bit and 32-bit timers (TIMER1 and TIMER4) and provides a complete set of configuration options, interrupt handling, DMA support, and various timer modes including PWM, input capture, and quadrature decoder.


339-339: Missing value assignment for TIMER_INT_FLAG_BRK

The macro definition is incomplete and will cause compilation errors.

Apply this fix:

-#define TIMER_INT_FLAG_BRK                  TIMER_INTF_BRKIF
+#define TIMER_INT_FLAG_BRK                  TIMER_INTF_BRKIF                        /*!< break interrupt flag */

Likely an incorrect or invalid review comment.

lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Include/gd32f4xx_adc.h (6)

1-34: License header looks good.

The BSD 3-clause license is properly formatted and includes all required clauses.


40-44: ADC base address definitions are correct.

The peripheral offsets follow a standard pattern for multi-ADC systems.


45-70: Register definitions are well-structured.

The register layout correctly separates individual ADC registers from shared synchronization registers, following standard ARM peripheral conventions.


336-354: ADC channel definitions are complete and correct.

The channel definitions properly include both external channels (0-15) and internal channels (16-18) for temperature sensor, voltage reference, and battery voltage monitoring.


199-212: Excellent multi-ADC synchronization support.

The implementation provides comprehensive synchronization modes for dual and triple ADC configurations, which is valuable for applications requiring coordinated sampling like motor control and power conversion systems.

Also applies to: 500-512


35-512: Well-structured ADC driver header implementation.

This header file provides a comprehensive and well-organized interface for the GD32F4xx ADC peripheral. The structure follows established patterns from similar ARM Cortex-M microcontroller libraries, making it familiar to embedded developers. The support for multi-ADC synchronization and extensive configuration options makes this suitable for complex applications.

The only improvements needed are minor style fixes (comma spacing) and adding a newline at the end of the file.

@ledvinap
Copy link
Contributor

ledvinap commented Jul 9, 2025

@jianpingwu1 : Don't bother about @coderabbitai for third-party library.

@coderabbitai : This is library provided by Giga Device. Check only for critical BF related errors. Other problems must be handled upstream.

@coderabbitai
Copy link
Contributor

coderabbitai bot commented Jul 9, 2025

Tip

For best results, initiate chat on the files or code changes.

@ledvinap Understood. I’ll restrict my review of the GD32F4 vendor library to Betaflight-critical integration issues only and leave upstream matters untouched.


🧠 Learnings used
Learnt from: jianpingwu1
PR: betaflight/betaflight#14519
File: lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_can.c:110-110
Timestamp: 2025-07-09T09:22:27.093Z
Learning: In Betaflight GD32F4 firmware library integration, typos and minor issues in vendor-supplied code from GigaDevice Semiconductor are kept as-is to maintain synchronization with upstream library updates, avoiding local modifications that could complicate future library version updates.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/main/drivers/nvic.h:105-111
Timestamp: 2025-07-08T03:54:32.159Z
Learning: PR #14520 for GD32F4 platform source support has a dependency on a separate GD32F4 firmware library PR that contains vendor header definitions like NVIC_PRIGROUP_PRE2_SUB2. The library PR should be merged before the source PR to avoid build failures.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14519
File: lib/main/GD32F4/Drivers/CMSIS/core_cmFunc.h:515-521
Timestamp: 2025-07-09T09:07:56.651Z
Learning: In PR #14519 for GD32F4 firmware library support, the main CMSIS library files from lib/main/CMSIS are used instead of the GD32F4-specific CMSIS files in lib/main/GD32F4/Drivers/CMSIS/. Unused duplicate CMSIS files in the GD32F4 directory should be removed to avoid confusion and maintain clean project structure.

Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: PR #14378 increases the PINIO limit from 4 to 8 to support flight controllers that use analog switches driven by GPIOs, requiring more configurable pins.

Learnt from: blckmn
PR: betaflight/betaflight#14437
File: src/main/build/build_config.h:66-66
Timestamp: 2025-06-09T09:15:59.886Z
Learning: RP2350 MCU support in Betaflight is being added incrementally, with the enum definitions for MCU_TYPE_RP2350A and MCU_TYPE_RP2350B added first in build_config.h, while platform implementation may be in a separate branch or coming in subsequent commits.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/platform/GD32/dshot_bitbang_stdperiph.c:116-116
Timestamp: 2025-07-08T07:48:44.853Z
Learning: In Betaflight's GD32 platform, the drivers/dma.h header automatically includes platform/dma.h, so GD32-specific DMA functions like gd32_dma_chbase_parse are available when including drivers/dma.h without needing to explicitly include platform/dma.h.

Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: In Betaflight PR #14378, increasing the PINIO limit from 4 to 8 required only changing the PINIO_COUNT macro definition in src/main/drivers/pinio.h, as all array sizes and loops throughout the codebase reference this constant.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/platform/GD32/pwm_output_dshot.c:166-171
Timestamp: 2025-07-08T07:52:07.162Z
Learning: GD32F4 timer channel DMA hardware requires the second data element in DShot DMA buffers to appear twice. This necessitates a memmove operation in pwmCompleteDshotMotorUpdate() to shift buffer elements and duplicate the second data element at positions [1] and [2].

@jianpingwu1
Copy link
Contributor Author

@jianpingwu1 : Don't bother about @coderabbitai for third-party library.

@coderabbitai : This is library provided by Giga Device. Check only for critical BF related errors. Other problems must be handled upstream.

OK, Thanks for the comment. And I will evaluate whether the AI-checked issues have an impact on BF.

@coderabbitai
Copy link
Contributor

coderabbitai bot commented Jul 9, 2025

Tip

For best results, initiate chat on the files or code changes.

@jianpingwu1 Perfect! That's exactly the right approach. You can focus on evaluating any findings for their potential impact on Betaflight's core functionality while leaving vendor-specific library issues to be handled upstream.

Feel free to tag me if you need help analyzing whether any specific issues might affect Betaflight integration or if you'd like a second opinion on the criticality of any findings.

🐰
/| /|
( ✌️ )
|(_)|


🧠 Learnings used
Learnt from: jianpingwu1
PR: betaflight/betaflight#14519
File: lib/main/GD32F4/Drivers/GD32F4xx_standard_peripheral/Source/gd32f4xx_can.c:110-110
Timestamp: 2025-07-09T09:22:27.093Z
Learning: In Betaflight GD32F4 firmware library integration, typos and minor issues in vendor-supplied code from GigaDevice Semiconductor are kept as-is to maintain synchronization with upstream library updates, avoiding local modifications that could complicate future library version updates.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/main/drivers/nvic.h:105-111
Timestamp: 2025-07-08T03:54:32.159Z
Learning: PR #14520 for GD32F4 platform source support has a dependency on a separate GD32F4 firmware library PR that contains vendor header definitions like NVIC_PRIGROUP_PRE2_SUB2. The library PR should be merged before the source PR to avoid build failures.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14519
File: lib/main/GD32F4/Drivers/CMSIS/core_cmFunc.h:515-521
Timestamp: 2025-07-09T09:07:56.651Z
Learning: In PR #14519 for GD32F4 firmware library support, the main CMSIS library files from lib/main/CMSIS are used instead of the GD32F4-specific CMSIS files in lib/main/GD32F4/Drivers/CMSIS/. Unused duplicate CMSIS files in the GD32F4 directory should be removed to avoid confusion and maintain clean project structure.

Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: PR #14378 increases the PINIO limit from 4 to 8 to support flight controllers that use analog switches driven by GPIOs, requiring more configurable pins.

Learnt from: blckmn
PR: betaflight/betaflight#14437
File: src/main/build/build_config.h:66-66
Timestamp: 2025-06-09T09:15:59.886Z
Learning: RP2350 MCU support in Betaflight is being added incrementally, with the enum definitions for MCU_TYPE_RP2350A and MCU_TYPE_RP2350B added first in build_config.h, while platform implementation may be in a separate branch or coming in subsequent commits.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/platform/GD32/dshot_bitbang_stdperiph.c:116-116
Timestamp: 2025-07-08T07:48:44.853Z
Learning: In Betaflight's GD32 platform, the drivers/dma.h header automatically includes platform/dma.h, so GD32-specific DMA functions like gd32_dma_chbase_parse are available when including drivers/dma.h without needing to explicitly include platform/dma.h.

Learnt from: heronprecision-1
PR: betaflight/betaflight#14378
File: src/main/pg/piniobox.c:73-76
Timestamp: 2025-05-13T18:41:35.781Z
Learning: In Betaflight PR #14378, increasing the PINIO limit from 4 to 8 required only changing the PINIO_COUNT macro definition in src/main/drivers/pinio.h, as all array sizes and loops throughout the codebase reference this constant.

Learnt from: jianpingwu1
PR: betaflight/betaflight#14520
File: src/platform/GD32/pwm_output_dshot.c:166-171
Timestamp: 2025-07-08T07:52:07.162Z
Learning: GD32F4 timer channel DMA hardware requires the second data element in DShot DMA buffers to appear twice. This necessitates a memmove operation in pwmCompleteDshotMotorUpdate() to shift buffer elements and duplicate the second data element at positions [1] and [2].

@haslinghuis haslinghuis moved this to In Progress in 2025.12.0 Jul 9, 2025
@haslinghuis haslinghuis added this to the 4.6 milestone Jul 9, 2025
@haslinghuis haslinghuis removed this from 2025.12.0 Sep 1, 2025
@haslinghuis haslinghuis moved this to Todo in 2026.6.0 Sep 1, 2025
@haslinghuis haslinghuis moved this from Todo to In Progress in 2026.6.0 Sep 2, 2025
@haslinghuis haslinghuis moved this from In Progress to Platform in 2026.6.0 Oct 2, 2025
@blckmn blckmn merged commit d380999 into betaflight:master Nov 16, 2025
2 checks passed
@github-project-automation github-project-automation bot moved this from Hardware to Done in 2026.6.0 Nov 16, 2025
@haslinghuis haslinghuis removed this from 2026.6.0 Nov 16, 2025
L0puh pushed a commit to L0puh/betaflight that referenced this pull request Nov 17, 2025
L0puh pushed a commit to L0puh/betaflight that referenced this pull request Nov 17, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

Status: Done

Development

Successfully merging this pull request may close these issues.

4 participants