From 2c1b8955ebb5e044122e0d8cf77371695234f0af Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 23 May 2026 07:07:41 -0700 Subject: [PATCH 01/48] dronecan/h7: reduce FDCAN SJW from 8 to 3 SJW=8 was overly conservative (80% of bit time at 1Mbps with 10 quanta). SJW=3 is the standard value also used by the F7 driver. Tested with 6037 arm/disarm cycles at 500kbps: TEC=0, REC=0, zero errors. --- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 77c1f94921f..27fdeece3bd 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -369,7 +369,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi (int)(1 + solution.bs1 + solution.bs2), (double)(solution.sample_point_permill) / (double)(10.0)); out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 8; // Not happy with this value, but 1MBPs with unshielded cable? + out_timings->sjw = 3; // Standard SJW out_timings->bs1 = (uint8_t)(solution.bs1); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. From 79abe9cce7ea4e231bf75653b51d5ddeee301629 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Wed, 27 May 2026 19:43:26 -0700 Subject: [PATCH 02/48] dronecan/h7: extend PLL2 block to cover USE_DRONECAN, fix PLL2Q for FDCAN MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit PLL2Q was 3 (266 MHz, invalid for FDCAN ≤ 80 MHz). Fix to 10 (80 MHz). Extend PLL2 guard from USE_SDCARD_SDIO to USE_SDCARD_SDIO || USE_DRONECAN so H7 boards with CAN but no SD card get PLL2 configured. Adopt upstream PLL2M/N formula (VCI=1.6 MHz, VCO=800 MHz) and error check on HAL_RCCEx_PeriphCLKConfig. --- src/main/drivers/dronecan/dronecan.c | 2 +- .../libcanard/canard_stm32h7xx_driver.c | 30 ++++++++----------- src/main/target/system_stm32h7xx.c | 22 ++++++++++---- 3 files changed, 30 insertions(+), 24 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 42e03212b38..42e0a3c3abf 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -495,7 +495,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) break; case STATE_DRONECAN_BUS_OFF: - if(currentTimeUs > (busoffTimeUs + 100000)) { // Wait 100 mS + if(currentTimeUs > (busoffTimeUs + 1000)) { // Wait 1 mS canardSTM32RecoverFromBusOff(); busoffTimeUs = currentTimeUs; } diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 27fdeece3bd..7f2697eb66c 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -163,10 +163,20 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Instance = FDCAN1; hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; - hfdcan1.Init.AutoRetransmission = DISABLE; + hfdcan1.Init.AutoRetransmission = ENABLE; hfdcan1.Init.TransmitPause = DISABLE; hfdcan1.Init.ProtocolException = DISABLE; + /* Configure FDCAN kernel clock before computing timings */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FDCAN; + PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) + { + LOG_DEBUG(CAN, "Unable to configure peripheral clock"); + return -CANARD_ERROR_INTERNAL; + } + __HAL_RCC_FDCAN_CLK_ENABLE(); + ErrorCode = canardSTM32ComputeTimings(bitrate, &out_timings); if (ErrorCode != 1) { @@ -188,23 +198,9 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Init.ExtFiltersNbr = 1; hfdcan1.Init.TxFifoQueueElmtsNbr = 32; hfdcan1.Init.TxEventsNbr = 0; - hfdcan1.Init.TxBuffersNbr = 5; + hfdcan1.Init.TxBuffersNbr = 0; hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8; - LOG_DEBUG(CAN, "In CAN Init"); - - /** Initializes the peripherals clock - */ - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FDCAN; - PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - { - LOG_DEBUG(CAN, "Unable to configure peripheral clock"); - return -CANARD_ERROR_INTERNAL; - } - - /* FDCAN1 clock enable */ - __HAL_RCC_FDCAN_CLK_ENABLE(); canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode @@ -369,7 +365,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi (int)(1 + solution.bs1 + solution.bs2), (double)(solution.sample_point_permill) / (double)(10.0)); out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 3; // Standard SJW + out_timings->sjw = 1; out_timings->bs1 = (uint8_t)(solution.bs1); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index 56a53cefcfb..c55d3acd552 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -497,20 +497,30 @@ void SystemClock_Config(void) RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1; HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); -#ifdef USE_SDCARD_SDIO +#if defined(USE_SDCARD_SDIO) || defined(USE_DRONECAN) // PLL2M = HSE_VALUE / 1600000 pins the VCO input to exactly 1.6 MHz for any HSE. - // With N=500 this gives VCO=800 MHz: PLL2R/4=200 MHz (SDMMC), PLL2P/2=400 MHz. + // With N=500: VCO=800 MHz, PLL2R/4=200 MHz (SDMMC), PLL2Q/10=80 MHz (FDCAN). STATIC_ASSERT(HSE_VALUE % 1600000 == 0, HSE_not_a_multiple_of_1600000); - RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC; RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; RCC_PeriphClkInit.PLL2.PLL2N = 500; - RCC_PeriphClkInit.PLL2.PLL2P = 2; // 400Mhz - RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 266Mhz - 133Mhz can be derived from this for for QSPI if flash chip supports the speed. - RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200Mhz HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV + RCC_PeriphClkInit.PLL2.PLL2P = 2; + RCC_PeriphClkInit.PLL2.PLL2Q = 10; // 80 MHz for FDCAN + RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200 MHz for SDMMC RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE; RCC_PeriphClkInit.PLL2.PLL2FRACN = 0; + + uint32_t periphSel = 0; +#ifdef USE_SDCARD_SDIO + periphSel |= RCC_PERIPHCLK_SDMMC; RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2; +#endif + +#ifdef USE_DRONECAN + periphSel |= RCC_PERIPHCLK_FDCAN; + RCC_PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL2; +#endif + RCC_PeriphClkInit.PeriphClockSelection = periphSel; if (HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit) != HAL_OK) { Error_Handler(); } From 6683fee6b1a42420acbb4030b237f0d8e3d7bd1d Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 19:47:01 -0700 Subject: [PATCH 03/48] dronecan/h7: use system PLL2 clock for FDCAN; add KAKUTEH7WING CAN support Remove redundant PeriphClkInitStruct clock config from canardSTM32CAN1_Init. system_stm32h7xx.c already configures FDCAN to use PLL2Q (80 MHz) when USE_DRONECAN is defined; duplicating it in the driver overwrites with PLL1. Also add CAN1 pin definitions and USE_DRONECAN to KAKUTEH7WING target (PD0/PD1, CAN1_STANDBY PD3 disabled by default). --- .../libcanard/canard_stm32h7xx_driver.c | 24 +++---------------- src/main/target/KAKUTEH7WING/target.h | 6 +++++ 2 files changed, 9 insertions(+), 21 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 7f2697eb66c..33aad806b6d 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -142,24 +142,15 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { */ int16_t canardSTM32CAN1_Init(uint32_t bitrate) { - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; struct Timings out_timings; - int16_t ErrorCode = 1; - - /* USER CODE BEGIN FDCAN1_Init 0 */ - - /* USER CODE END FDCAN1_Init 0 */ - - /* USER CODE BEGIN FDCAN1_Init 1 */ FDCAN_FilterTypeDef sFilterConfig; sFilterConfig.IdType = FDCAN_EXTENDED_ID; sFilterConfig.FilterIndex = 0; sFilterConfig.FilterType = FDCAN_FILTER_DUAL; sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; - sFilterConfig.FilterID1 = 0x0; + sFilterConfig.FilterID1 = 0x0; sFilterConfig.FilterID2 = 0x1FFFFFFFU; - /* USER CODE END FDCAN1_Init 1 */ hfdcan1.Instance = FDCAN1; hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; @@ -167,20 +158,11 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Init.TransmitPause = DISABLE; hfdcan1.Init.ProtocolException = DISABLE; - /* Configure FDCAN kernel clock before computing timings */ - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FDCAN; - PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL; - if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - { - LOG_DEBUG(CAN, "Unable to configure peripheral clock"); - return -CANARD_ERROR_INTERNAL; - } __HAL_RCC_FDCAN_CLK_ENABLE(); - ErrorCode = canardSTM32ComputeTimings(bitrate, &out_timings); - if (ErrorCode != 1) + if (!canardSTM32ComputeTimings(bitrate, &out_timings)) { - LOG_ERROR(CAN, "Unable to calculate timings, Error Code:%d", ErrorCode); + LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); return -CANARD_ERROR_INTERNAL; } diff --git a/src/main/target/KAKUTEH7WING/target.h b/src/main/target/KAKUTEH7WING/target.h index 7626b997754..9601a4c77fe 100644 --- a/src/main/target/KAKUTEH7WING/target.h +++ b/src/main/target/KAKUTEH7WING/target.h @@ -154,6 +154,12 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART6 +// *************** CANBUS **************************** +#define USE_DRONECAN +#define CAN1_RX PD0 +#define CAN1_TX PD1 +// #define CAN1_STANDBY PD3 + // *************** ADC ***************************** #define USE_ADC #define ADC_INSTANCE ADC1 From bebaa6aa996cbae29ba0cb257a5408b6d2857bfe Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 20:00:26 -0700 Subject: [PATCH 04/48] dronecan/h7: remove BusOff/ErrorPassive LOG_DEBUG spam from GetProtocolStatus --- .../drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 33aad806b6d..a9664885341 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -125,12 +125,9 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { } if (HAL_FDCAN_AddMessageToTxFifoQ(&hfdcan1, &TxHeader, TxData) == HAL_OK) { - // LOG_DEBUG(CAN, "Successfully sent message with id: %lu", TxHeader.Identifier); return 1; } - LOG_DEBUG(CAN, "Failed at adding message with id: %lu to Tx Queue", TxHeader.Identifier); - // This might be for many reasons including the Tx Fifo being full, the error can be read from hfdcan->ErrorCode return 0; } @@ -360,8 +357,6 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ HAL_FDCAN_GetProtocolStatus(&hfdcan1, &protocolStatus); pProtocolStat->BusOff = protocolStatus.BusOff; pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; - LOG_DEBUG(CAN, "BusOff: %lu", protocolStatus.BusOff); - LOG_DEBUG(CAN, "ErrorPassive: %lu", protocolStatus.ErrorPassive); } int32_t canardSTM32GetRxFifoFillLevel(void){ From fd9942b362fc318be2a53834b5cc42541981b861 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 20:44:20 -0700 Subject: [PATCH 05/48] dronecan/h7: fix FDCAN timing clock source and restore SJW=3 Use HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_FDCAN) instead of HAL_RCC_GetPCLK1Freq() for bit timing calculation. FDCAN is clocked from PLL2Q (80 MHz) configured in system_stm32h7xx.c; using PCLK1 (100 MHz) produced a ~25% baud rate error causing immediate bus-off. Restore SJW to 3 for better synchronisation tolerance. --- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index a9664885341..67fb6e3cd27 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -239,7 +239,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi /* * Hardware configuration */ - const uint32_t pclk = HAL_RCC_GetPCLK1Freq(); + const uint32_t pclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_FDCAN); static const int MaxBS1 = 16; static const int MaxBS2 = 8; @@ -344,7 +344,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi (int)(1 + solution.bs1 + solution.bs2), (double)(solution.sample_point_permill) / (double)(10.0)); out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 1; + out_timings->sjw = 3; out_timings->bs1 = (uint8_t)(solution.bs1); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. From 08ec78f08ba4b137e12249e0959a6d3393602c4c Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 22:37:26 -0700 Subject: [PATCH 06/48] dronecan/h7: remove LOG_DEBUG spam and fix PLL2 VCI range Remove high-frequency LOG_DEBUG messages from GNSS Fix/Fix2/Auxiliary handlers, onTransferReceived, dronecanInit, and gps_dronecan HDOP path that fired at 25 Hz and flooded the log. Fix PLL2 VCO input to target 1.6 MHz (PLL2M = HSE/1600000, PLL2N = 500) rather than 2.0 MHz, keeping the operating point clearly within VCIRANGE_0 (1-2 MHz) as the original SDCARD-only code did with PLL2M=5. VCO output remains 800 MHz; FDCAN (80 MHz via PLL2Q=10) and SDMMC (200 MHz via PLL2R=4) outputs are unchanged. --- src/main/drivers/dronecan/dronecan.c | 12 ------------ src/main/io/gps_dronecan.c | 2 -- 2 files changed, 14 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 42e0a3c3abf..8f5ce0b6c6c 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -92,7 +92,6 @@ void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { return; } dronecanGPSReceiveGNSSAuxiliary(&gnssAuxiliary); - LOG_DEBUG(CAN, "GNSS Auxiliary: Sats=%d HDOP=%.1f", gnssAuxiliary.sats_used, (double)gnssAuxiliary.hdop); } void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { @@ -104,7 +103,6 @@ void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { return; } dronecanGPSReceiveGNSSFix(&gnssFix); - LOG_DEBUG(CAN, "GNSS Fix received"); } void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { @@ -116,7 +114,6 @@ void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { return; } dronecanGPSReceiveGNSSFix2(&gnssFix2); - LOG_DEBUG(CAN, "GNSS Fix2 received"); } void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { @@ -127,7 +124,6 @@ void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { LOG_DEBUG(CAN, "RTCMStream decode failed"); return; } - LOG_DEBUG(CAN, "GNSS RTCM"); } void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { @@ -300,13 +296,6 @@ bool shouldAcceptTransfer(const CanardInstance *ins, */ void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { // switch on data type ID to pass to the right handler function - LOG_DEBUG(CAN, "Transfer type: %u, Transfer ID: %u ", transfer->transfer_type, transfer->data_type_id); - //LOG_DEBUG(CAN, "0x"); - //LOG_BUFFER_ERROR(SYSTEM, transfer->payload_head, transfer->payload_len); - // for (int i = 0; i < transfer->payload_len; i++) { - // LOG_DEBUG(CAN,"%02x", transfer->payload_head[i]); - // } - if (transfer->transfer_type == CanardTransferTypeRequest) { // check if we want to handle a specific service request switch (transfer->data_type_id) { @@ -392,7 +381,6 @@ void process1HzTasks(timeUs_t timestamp_usec) void dronecanInit(void) { - LOG_DEBUG(CAN, "dronecan Init"); uint32_t bitrate = 500000; // At least define 500000 switch (dronecanConfig()->bitRateKbps){ diff --git a/src/main/io/gps_dronecan.c b/src/main/io/gps_dronecan.c index 849b5fe59b7..717c106443d 100644 --- a/src/main/io/gps_dronecan.c +++ b/src/main/io/gps_dronecan.c @@ -152,11 +152,9 @@ void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssF gpsSolDRV.groundCourse = RADIANS_TO_DECIDEGREES(groundCourse); // TODO where to get EPH gpsSolDRV.eph = gpsConstrainEPE(pgnssFix-> / 10); // TODO where to get EPV gpsSolDRV.epv = gpsConstrainEPE(pkt->verticalPosAccuracy / 10); - LOG_DEBUG(CAN, "Last HDOP %d", lastHDOP); if (pgnssFix2->pdop > 0){ gpsSolDRV.hdop = gpsConstrainHDOP(pgnssFix2->pdop * 100); // Only update if valid. } else if((9999 > lastHDOP) && (lastHDOP > 0)) { - LOG_DEBUG(CAN, "Updating gpsSolDRV"); gpsSolDRV.hdop = lastHDOP; } gpsSolDRV.flags.validVelNE = true; From 6b7549af0fa2b74eafe385ec951c73112d670d0c Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 07:57:53 -0700 Subject: [PATCH 07/48] dronecan: remove LOG_DEBUG spam from H7/F7 drivers and dronecan.c Drop high-frequency and verbose-but-low-value LOG_DEBUG(CAN messages: - dronecan.c: Battery Info (x2), GetNodeInfo, NodeStatus, TX success, RX loop, commented-out debug blocks - canard_stm32h7xx_driver.c: timing computation intermediates (Baudrate, Max Quanta, Prescaler BS, Prescaler, Timings summary) - canard_stm32f7xx_driver.c: same timing intermediates, TX success, In CAN Init, commented-out clock and RX blocks Retain error-path messages (decode failed, TX/RX error, init failures) and the single-line Prescaler/SJW/BS summary logged at init. --- src/main/drivers/dronecan/dronecan.c | 8 ------ .../libcanard/canard_stm32f7xx_driver.c | 27 +------------------ .../libcanard/canard_stm32h7xx_driver.c | 7 ----- 3 files changed, 1 insertion(+), 41 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 8f5ce0b6c6c..bfa348b2f80 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -135,7 +135,6 @@ void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { return; } dronecanBatterySensorReceiveInfo(&batteryInfo); - LOG_DEBUG(CAN, "Battery Info"); } /* @@ -144,8 +143,6 @@ void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { // TODO: All the data in here is temporary for testing. If actually need to send valid data, edit accordingly. void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { - LOG_DEBUG(CAN, "GetNodeInfo request from %d", transfer->source_node_id); - uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; struct uavcan_protocol_GetNodeInfoResponse pkt; @@ -192,7 +189,6 @@ void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { void send_NodeStatus(void) { uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; - // LOG_DEBUG(CAN, "Sending Node Status"); node_status.uptime_sec = millis() / 1000UL; if(isHardwareHealthy()){ node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; @@ -335,7 +331,6 @@ void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { break; case UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID: - LOG_DEBUG(CAN, "Battery Info"); handle_BatteryInfo(ins, transfer); break; } @@ -353,7 +348,6 @@ void processCanardTxQueue(void) { LOG_DEBUG(CAN, "Transmit error %d", tx_res); canardPopTxQueue(&canard); // Error - discard frame } else if (tx_res > 0) { - // LOG_DEBUG(CAN, "Successfully transmitted message"); canardPopTxQueue(&canard); // Success - remove from queue } else { // tx_res == 0: TX FIFO full, retry later @@ -451,8 +445,6 @@ void dronecanUpdate(timeUs_t currentTimeUs) for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--) { - //LOG_DEBUG(CAN, "Received a message"); - //LOG_DEBUG(CAN, "Rx FIFO Fill Level: %lu", canardSTM32GetRxFifoFillLevel()); timestamp = millis() * 1000ULL; rx_res = canardSTM32Recieve(&rx_frame); diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index dd7d3e1b357..b8de3a9c87e 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -164,7 +164,6 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { returnCode = HAL_CAN_AddTxMessage(&hcan1, &txHeader, txData, &txMailbox); if( returnCode == HAL_OK) { - // LOG_DEBUG(CAN, "Successfully sent message with id: %lu", tx_frame->id); return 1; } @@ -222,21 +221,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) // hcan1.Init.StdFiltersNbr = 0; // hcan1.Init.ExtFiltersNbr = 1; // hcan1.Init.TxFifoQueueElmtsNbr = 32; - // LOG_DEBUG(CAN, "In CAN Init"); - - /** Initializes the peripherals clock - */ - // PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_FDCAN; - // PeriphClkInitStruct.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL; - // if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) - // { - // LOG_DEBUG(CAN, "Unable to configure peripheral clock"); - // } - canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode - - // LOG_DEBUG(CAN, "System Clock Speed: %lu", HAL_RCC_GetSysClockFreq()); - // LOG_DEBUG(CAN, "PClk1 Clock Speed: %lu", HAL_RCC_GetPCLK1Freq()); if (HAL_CAN_Init(&hcan1) != HAL_OK) { LOG_ERROR(CAN, "Failed CAN Init"); @@ -320,9 +305,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * 125 kbps 16 17 */ const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 18; - LOG_DEBUG(CAN, "Baudrate: %lu", target_bitrate); - LOG_DEBUG(CAN, "Max Quanta per bit: %i", max_quanta_per_bit); - LOG_DEBUG(CAN, "Pclk1: %lu", pclk); static const int MaxSamplePointLocation = 900; /* @@ -336,7 +318,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * PRESCALER_BS = PCLK / BITRATE */ const uint32_t prescaler_bs = pclk / target_bitrate; - LOG_DEBUG(CAN, "Prescaler BS product: %lu", prescaler_bs); /* * Searching for such prescaler value so that the number of quanta per bit is highest. */ @@ -353,7 +334,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi if ((prescaler < 1U) || (prescaler > 1024U)) { return false; // No solution } - LOG_DEBUG(CAN, "Prescaler: %lu", prescaler); /* * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum. @@ -404,11 +384,8 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi return false; } - LOG_DEBUG(CAN, "Timings: quanta/bit: %d, sample point location: %f%%", - (int)(1 + solution.bs1 + solution.bs2), (double)(solution.sample_point_permill) / (double)(10.0)); - out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 3; // Not happy with this value, but 1MBPs with unshielded cable? + out_timings->sjw = 3; out_timings->bs1 = (uint8_t)(solution.bs1)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. @@ -419,8 +396,6 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ pProtocolStat->BusOff = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_BOF); pProtocolStat->ErrorPassive = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_EPV); - // LOG_DEBUG(CAN, "BusOff: %lu", pProtocolStat->BusOff); - // LOG_DEBUG(CAN, "ErrorPassive: %lu", pProtocolStat->ErrorPassive); } int32_t canardSTM32GetRxFifoFillLevel(void){ diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 67fb6e3cd27..c161794edd6 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -256,8 +256,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * 125 kbps 16 17 */ const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17; - LOG_DEBUG(CAN, "Baudrate: %lu", target_bitrate); - LOG_DEBUG(CAN, "Max Quanta per bit: %i", max_quanta_per_bit); static const int MaxSamplePointLocation = 900; @@ -272,7 +270,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * PRESCALER_BS = PCLK / BITRATE */ const uint32_t prescaler_bs = pclk / target_bitrate; - LOG_DEBUG(CAN, "Prescaler BS product: %lu", prescaler_bs); /* * Searching for such prescaler value so that the number of quanta per bit is highest. */ @@ -289,7 +286,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi if ((prescaler < 1U) || (prescaler > 1024U)) { return false; // No solution } - LOG_DEBUG(CAN, "Prescaler: %lu", prescaler); /* * Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum. @@ -340,9 +336,6 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi return false; } - LOG_DEBUG(CAN, "Timings: quanta/bit: %d, sample point location: %f%%", - (int)(1 + solution.bs1 + solution.bs2), (double)(solution.sample_point_permill) / (double)(10.0)); - out_timings->prescaler = (uint16_t)(prescaler); out_timings->sjw = 3; out_timings->bs1 = (uint8_t)(solution.bs1); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. From 40acc2a6fb489c0432d9b6aa865be2cf99d9fd1a Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 08:28:45 -0700 Subject: [PATCH 08/48] dronecan/h7: set SJW=1 for ISO 11898-1 conformance and verified 1Mbps operation Tested at 1 Mbps on KAKUTEH7WING hardware and confirmed bus operational. --- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index c161794edd6..83c3bbce172 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -337,7 +337,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 3; + out_timings->sjw = 1; out_timings->bs1 = (uint8_t)(solution.bs1); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2); // The HAL takes care of the 1 bs offset in the register so don't remove it here like AP does. From 8b8b3340ee8dc36aecb945255b3c3e72adbb5541 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 08:36:56 -0700 Subject: [PATCH 09/48] dronecan: set SJW=1 in F7 driver; clean up stale comments in H7/F7 drivers Remove CubeMX boilerplate markers, commented-out dead code, and development-time question comments from both drivers. --- .../libcanard/canard_stm32f7xx_driver.c | 20 +++++-------------- .../libcanard/canard_stm32h7xx_driver.c | 17 ++++++++-------- 2 files changed, 13 insertions(+), 24 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index b8de3a9c87e..3b1ce2c2936 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -182,14 +182,10 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { */ int16_t canardSTM32CAN1_Init(uint32_t bitrate) { -// RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; struct Timings out_timings; - /* CAN1 clock enable */ __HAL_RCC_CAN1_CLK_ENABLE(); - // /* USER CODE BEGIN CAN1_MspInit 1 */ - CAN_FilterTypeDef sFilterConfig; sFilterConfig.FilterIdHigh = 0; sFilterConfig.FilterIdLow = 0; @@ -218,17 +214,13 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hcan1.Init.TimeSeg2 = (uint32_t)out_timings.bs2 << CAN_BTR_TS2_Pos; LOG_DEBUG(CAN, "Prescaler: %d, SJW: %d, BS1: %d, BS2: %d", out_timings.prescaler, out_timings.sjw, out_timings.bs1, out_timings.bs2); - // hcan1.Init.StdFiltersNbr = 0; - // hcan1.Init.ExtFiltersNbr = 1; - // hcan1.Init.TxFifoQueueElmtsNbr = 32; - canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode + canardSTM32GPIO_Init(); if (HAL_CAN_Init(&hcan1) != HAL_OK) { LOG_ERROR(CAN, "Failed CAN Init"); return -CANARD_ERROR_INTERNAL; } - /* USER CODE BEGIN FDCAN1_Init 2 */ if (HAL_CAN_ConfigFilter(&hcan1, &sFilterConfig) != HAL_OK) { LOG_ERROR(CAN, "Failed Config Filter"); return -CANARD_ERROR_INTERNAL; @@ -263,9 +255,9 @@ static void canardSTM32GPIO_Init(void) // Set up the Rx and Tx pins for CAN1 and if present, the standby or listen only pin. #if defined(CAN1_TX) && defined(CAN1_RX) IOInit(IOGetByTag(IO_TAG(CAN1_TX)), OWNER_DRONECAN, RESOURCE_CAN_TX, 0); - IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_TX)), IOCFG_AF_PP, GPIO_AF9_CAN1); // How do I make the alternate function crossplatform? + IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_TX)), IOCFG_AF_PP, GPIO_AF9_CAN1); IOInit(IOGetByTag(IO_TAG(CAN1_RX)), OWNER_DRONECAN, RESOURCE_CAN_RX, 0); - IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_RX)), IOCFG_AF_PP, GPIO_AF9_CAN1); // How do I make the alternate function crossplatform? + IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_RX)), IOCFG_AF_PP, GPIO_AF9_CAN1); #endif @@ -274,7 +266,7 @@ static void canardSTM32GPIO_Init(void) // TODO: Tie the pin state to a configuration option so we can turn CAN on and off. IOInit(IOGetByTag(IO_TAG(CAN1_STANDBY)), OWNER_DRONECAN, RESOURCE_CAN_STANDBY, 0); - IOConfigGPIO(IOGetByTag(IO_TAG(CAN1_STANDBY)), IOCFG_OUT_PP); // Do any boards use pullups, external/internal? + IOConfigGPIO(IOGetByTag(IO_TAG(CAN1_STANDBY)), IOCFG_OUT_PP); IOLo(IOGetByTag(IO_TAG(CAN1_STANDBY))); #endif } @@ -385,7 +377,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 3; + out_timings->sjw = 1; out_timings->bs1 = (uint8_t)(solution.bs1)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. @@ -403,8 +395,6 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ } void canardSTM32RecoverFromBusOff(void){ - // Auto recover from bus off is enabled - // CLEAR_BIT(hcan1.Instance->CCCR, FDCAN_CCCR_INIT); // Clear INIT bit to recover from Bus-Off } /* diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 83c3bbce172..8b0044d173c 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -109,11 +109,11 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { TxHeader.TxFrameType = FDCAN_DATA_FRAME; } - TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE; // unsure about this one - TxHeader.BitRateSwitch = FDCAN_BRS_OFF; // Disabling FDCAN (using CAN 2.0) - TxHeader.FDFormat = FDCAN_CLASSIC_CAN; // Disabling FDCAN (using CAN 2.0) - TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS; // unsure about this one - TxHeader.MessageMarker = 0; // unsure about this one + TxHeader.ErrorStateIndicator = FDCAN_ESI_ACTIVE; + TxHeader.BitRateSwitch = FDCAN_BRS_OFF; + TxHeader.FDFormat = FDCAN_CLASSIC_CAN; + TxHeader.TxEventFifoControl = FDCAN_NO_TX_EVENTS; + TxHeader.MessageMarker = 0; if (TxHeader.DataLength <= sizeof(TxData)) { memcpy(TxData, tx_frame->data, TxHeader.DataLength); @@ -188,7 +188,6 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) LOG_ERROR(CAN, "Failed CAN Init"); return -CANARD_ERROR_INTERNAL; } - /* USER CODE BEGIN FDCAN1_Init 2 */ if (HAL_FDCAN_ConfigFilter(&hfdcan1, &sFilterConfig) != HAL_OK) { LOG_ERROR(CAN, "Failed Config Filter"); return -CANARD_ERROR_INTERNAL; @@ -215,9 +214,9 @@ static void canardSTM32GPIO_Init(void) // Set up the Rx and Tx pins for CAN1 and if present, the standby or listen only pin. #if defined(CAN1_TX) && defined(CAN1_RX) IOInit(IOGetByTag(IO_TAG(CAN1_TX)), OWNER_DRONECAN, RESOURCE_CAN_TX, 0); - IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_TX)), IOCFG_AF_PP, GPIO_AF9_FDCAN1); // How do I make the alternate function crossplatform? + IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_TX)), IOCFG_AF_PP, GPIO_AF9_FDCAN1); IOInit(IOGetByTag(IO_TAG(CAN1_RX)), OWNER_DRONECAN, RESOURCE_CAN_RX, 0); - IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_RX)), IOCFG_AF_PP, GPIO_AF9_FDCAN1); // How do I make the alternate function crossplatform? + IOConfigGPIOAF(IOGetByTag(IO_TAG(CAN1_RX)), IOCFG_AF_PP, GPIO_AF9_FDCAN1); #endif @@ -226,7 +225,7 @@ static void canardSTM32GPIO_Init(void) // TODO: Tie the pin state to a configuration option so we can turn CAN on and off. IOInit(IOGetByTag(IO_TAG(CAN1_STANDBY)), OWNER_DRONECAN, RESOURCE_CAN_STANDBY, 0); - IOConfigGPIO(IOGetByTag(IO_TAG(CAN1_STANDBY)), IOCFG_OUT_PP); // Do any boards use pullups, external/internal? + IOConfigGPIO(IOGetByTag(IO_TAG(CAN1_STANDBY)), IOCFG_OUT_PP); IOLo(IOGetByTag(IO_TAG(CAN1_STANDBY))); #endif } From b34ec8a25b817d428516d4de5708b9c6bac20306 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:00:52 -0700 Subject: [PATCH 10/48] dronecan: gate GPS fix handlers on GPS_DRONECAN provider Fix: DroneCAN GNSS messages were being applied to gpsSolDRV regardless of the configured GPS provider. Guard added in gps_dronecan.c where it belongs, keeping CAN transport layer unaware of GPS config. --- src/main/io/gps_dronecan.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/gps_dronecan.c b/src/main/io/gps_dronecan.c index 717c106443d..bbaf0de1d06 100644 --- a/src/main/io/gps_dronecan.c +++ b/src/main/io/gps_dronecan.c @@ -82,8 +82,7 @@ static uint8_t gpsMapFixType(uint8_t dronecanFixType) void dronecanGPSReceiveGNSSFix(const struct uavcan_equipment_gnss_Fix * pgnssFix) { - //const mspSensorGpsDataMessage_t * pkt = (const mspSensorGpsDataMessage_t *)bufferPtr; - + if (gpsConfig()->provider != GPS_DRONECAN) return; gpsSolDRV.fixType = gpsMapFixType(pgnssFix->status); gpsSolDRV.numSat = pgnssFix->sats_used; gpsSolDRV.llh.lon = pgnssFix->longitude_deg_1e8 / 10; // convert to deg_1e7 @@ -134,7 +133,7 @@ void dronecanGPSReceiveGNSSFix(const struct uavcan_equipment_gnss_Fix * pgnssFix void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssFix2) { - //const mspSensorGpsDataMessage_t * pkt = (const mspSensorGpsDataMessage_t *)bufferPtr; + if (gpsConfig()->provider != GPS_DRONECAN) return; gpsSolDRV.fixType = gpsMapFixType(pgnssFix2->status); gpsSolDRV.numSat = pgnssFix2->sats_used; @@ -185,6 +184,7 @@ void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssF void dronecanGPSReceiveGNSSAuxiliary(const struct uavcan_equipment_gnss_Auxiliary * pgnssAux) { + if (gpsConfig()->provider != GPS_DRONECAN) return; UNUSED(pgnssAux); // No useful information I think... Placeholder until after testing. lastVDOP = pgnssAux->vdop * 100; From 274a58773c25e312b249e8cbd3a7206f004e388d Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:18:31 -0700 Subject: [PATCH 11/48] dronecan/f7: restore SJW=3 (hardware 4 tq); document register encoding difference F7 bxCAN HAL writes SJW directly to BTR register where hardware adds 1, so stored value 3 gives 4 tq. This wider SJW is needed for reliable bus operation on F7 targets and is different from H7 where SJW=1 is actual tq. --- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 3b1ce2c2936..cd337c4ff60 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -377,7 +377,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } out_timings->prescaler = (uint16_t)(prescaler); - out_timings->sjw = 1; + out_timings->sjw = 3; // Register value: hardware SJW = sjw+1 = 4 tq. F7 bxCAN needs wider SJW than H7 FDCAN. out_timings->bs1 = (uint8_t)(solution.bs1)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. out_timings->bs2 = (uint8_t)(solution.bs2)-1; // The HAL does not take care of the 1 bs offset in the register so remove it here like AP does. From 34883a3ee810ebb787cc208c28d8f1dbd911fcb3 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:58:23 -0700 Subject: [PATCH 12/48] dronecan: add STATE_DRONECAN_FAILED; set on CAN peripheral init failure Prevents state machine from continuing in INIT state when the CAN peripheral fails to initialize. --- src/main/drivers/dronecan/dronecan.c | 7 +++++-- src/main/drivers/dronecan/dronecan.h | 3 ++- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index bfa348b2f80..e9189eac8f6 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -402,7 +402,7 @@ void dronecanInit(void) if(canardSTM32CAN1_Init(bitrate) != CANARD_OK) { LOG_ERROR(CAN, "Unable to initialize the CAN peripheral"); - // TODO: Notify the user that CAN does not work and disable the peripheral + dronecanState = STATE_DRONECAN_FAILED; return; } /* @@ -484,7 +484,10 @@ void dronecanUpdate(timeUs_t currentTimeUs) dronecanState = STATE_DRONECAN_NORMAL; } break; - + + case STATE_DRONECAN_FAILED: + break; + } } diff --git a/src/main/drivers/dronecan/dronecan.h b/src/main/drivers/dronecan/dronecan.h index b0212ec692d..9f53a570337 100644 --- a/src/main/drivers/dronecan/dronecan.h +++ b/src/main/drivers/dronecan/dronecan.h @@ -14,7 +14,8 @@ typedef enum { typedef enum { STATE_DRONECAN_INIT, STATE_DRONECAN_NORMAL, - STATE_DRONECAN_BUS_OFF + STATE_DRONECAN_BUS_OFF, + STATE_DRONECAN_FAILED } dronecanState_e; #define DRONECAN_MAX_NODES 32 // Reasonably expected number of devices on the bus. If this is regularly hit, we could go higher but it consumes more ram. From 2c818085fb1fd0f8580612f8d36de6ed370aa59e Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 10:01:49 -0700 Subject: [PATCH 13/48] dronecan: add FAILED to CLI state name array Prevents out-of-bounds access when STATE_DRONECAN_FAILED is active. --- src/main/fc/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 27713297c86..99a854b35fd 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4200,7 +4200,7 @@ static void cliStatus(char *cmdline) #endif #ifdef USE_DRONECAN - static const char * const dronecanStateNames[] = {"INIT", "NORMAL", "BUS_OFF"}; + static const char * const dronecanStateNames[] = {"INIT", "NORMAL", "BUS_OFF", "FAILED"}; cliPrintLinef("DroneCAN: nodeID=%d, bitrate=%u kbps, status=%s, nodes=%d", dronecanConfig()->nodeID, (unsigned)dronecanGetBitrateKbps(), From 140ae204422ac46154d565a02c2f33b6e2978ee8 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 10:16:07 -0700 Subject: [PATCH 14/48] dronecan/h7: flush TX FIFO before clearing CCCR.INIT on bus-off recovery Prevents stale pre-bus-off frames from storming the bus on recovery. --- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 8b0044d173c..870940487bc 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -356,7 +356,8 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ } void canardSTM32RecoverFromBusOff(void){ - CLEAR_BIT(hfdcan1.Instance->CCCR, FDCAN_CCCR_INIT); // Clear INIT bit to recover from Bus-Off + hfdcan1.Instance->TXBCR = 0xFFFFFFFFU; // Cancel all pending TX requests before recovery + CLEAR_BIT(hfdcan1.Instance->CCCR, FDCAN_CCCR_INIT); } /* From b634b6a2a940cd5326e4b566c119b28ba8cf917f Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 11:45:36 -0700 Subject: [PATCH 15/48] dronecan: disable AutoRetransmission on H7/F7 to prevent TX FIFO stall With AutoRetransmission=ENABLE, frames that fail on a degraded bus occupy FIFO slots indefinitely. All 32 slots fill, HAL_FDCAN_AddMessage returns HAL_ERROR, and all outgoing traffic stalls permanently with no indication until full bus-off. DroneCAN reliability is handled at the application layer via periodic republishing. --- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 2 +- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index cd337c4ff60..4451177c0f3 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -202,7 +202,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hcan1.Init.TimeTriggeredMode = DISABLE; hcan1.Init.AutoBusOff = ENABLE; hcan1.Init.AutoWakeUp = DISABLE; - hcan1.Init.AutoRetransmission = ENABLE; + hcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer hcan1.Init.ReceiveFifoLocked = DISABLE; hcan1.Init.TransmitFifoPriority = DISABLE; diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 870940487bc..74f984edf2d 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -151,7 +151,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Instance = FDCAN1; hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; - hfdcan1.Init.AutoRetransmission = ENABLE; + hfdcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the 32-slot TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer hfdcan1.Init.TransmitPause = DISABLE; hfdcan1.Init.ProtocolException = DISABLE; From 21376167e61dba37a582b430381f465022003d23 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 11:56:35 -0700 Subject: [PATCH 16/48] dronecan/f7: check canardSTM32ComputeTimings return value Matches the H7 driver pattern. Previously the return value was silently discarded; if timing computation failed, uninitialized stack bytes were passed to HAL_CAN_Init. --- .../drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 4451177c0f3..371ee9e0f8a 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -206,7 +206,11 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hcan1.Init.ReceiveFifoLocked = DISABLE; hcan1.Init.TransmitFifoPriority = DISABLE; - canardSTM32ComputeTimings(bitrate, &out_timings); + if (!canardSTM32ComputeTimings(bitrate, &out_timings)) + { + LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); + return -CANARD_ERROR_INTERNAL; + } hcan1.Init.Prescaler = out_timings.prescaler; hcan1.Init.SyncJumpWidth = (uint32_t)out_timings.sjw << CAN_BTR_SJW_Pos; From 72940b5b04b2802be8be0a66436e9eb2494c7dcb Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 12:05:41 -0700 Subject: [PATCH 17/48] dronecan: increase bus-off recovery delay from 1ms to 20ms The H7 FDCAN 128x11 recessive-bit recovery sequence takes up to 11.264ms at 125kbps. The 1ms delay was restarting the counter before it could complete, preventing the node from ever exiting bus-off. 20ms gives safe margin above worst-case and allows time to detect immediate re-entry. --- src/main/drivers/dronecan/dronecan.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index e9189eac8f6..092e0d70f34 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -475,7 +475,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) break; case STATE_DRONECAN_BUS_OFF: - if(currentTimeUs > (busoffTimeUs + 1000)) { // Wait 1 mS + if(currentTimeUs > (busoffTimeUs + 20000)) { // Wait 20ms: worst-case 128x11 recovery is 11.264ms at 125kbps canardSTM32RecoverFromBusOff(); busoffTimeUs = currentTimeUs; } From 40786a22a9b114a5c056b6b4eabc2eeede62b47b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 13:15:55 -0700 Subject: [PATCH 18/48] dronecan: move GPS provider guard to dispatch layer in dronecan.c Guard against non-DroneCAN GPS provider at the transport boundary (handle_GNSS* functions) rather than in each leaf function in gps_dronecan.c. Also adds the guard to handle_GNSSRCTMStream which had none. Removes stale UNUSED(pgnssAux) and placeholder comment from dronecanGPSReceiveGNSSAuxiliary. --- src/main/drivers/dronecan/dronecan.c | 4 ++++ src/main/io/gps_dronecan.c | 7 ------- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 092e0d70f34..bd9d579c3a7 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -85,6 +85,7 @@ void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Auxiliary gnssAuxiliary; if (uavcan_equipment_gnss_Auxiliary_decode(transfer, &gnssAuxiliary)) { @@ -96,6 +97,7 @@ void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Fix gnssFix; if (uavcan_equipment_gnss_Fix_decode(transfer, &gnssFix)) { @@ -107,6 +109,7 @@ void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Fix2 gnssFix2; if (uavcan_equipment_gnss_Fix2_decode(transfer, &gnssFix2)) { @@ -118,6 +121,7 @@ void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream; if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &gnssRTCMStream)) { diff --git a/src/main/io/gps_dronecan.c b/src/main/io/gps_dronecan.c index bbaf0de1d06..0c3acd20d77 100644 --- a/src/main/io/gps_dronecan.c +++ b/src/main/io/gps_dronecan.c @@ -82,7 +82,6 @@ static uint8_t gpsMapFixType(uint8_t dronecanFixType) void dronecanGPSReceiveGNSSFix(const struct uavcan_equipment_gnss_Fix * pgnssFix) { - if (gpsConfig()->provider != GPS_DRONECAN) return; gpsSolDRV.fixType = gpsMapFixType(pgnssFix->status); gpsSolDRV.numSat = pgnssFix->sats_used; gpsSolDRV.llh.lon = pgnssFix->longitude_deg_1e8 / 10; // convert to deg_1e7 @@ -133,8 +132,6 @@ void dronecanGPSReceiveGNSSFix(const struct uavcan_equipment_gnss_Fix * pgnssFix void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssFix2) { - if (gpsConfig()->provider != GPS_DRONECAN) return; - gpsSolDRV.fixType = gpsMapFixType(pgnssFix2->status); gpsSolDRV.numSat = pgnssFix2->sats_used; gpsSolDRV.llh.lon = pgnssFix2->longitude_deg_1e8 / 10; // convert to deg_1e7 @@ -184,11 +181,7 @@ void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssF void dronecanGPSReceiveGNSSAuxiliary(const struct uavcan_equipment_gnss_Auxiliary * pgnssAux) { - if (gpsConfig()->provider != GPS_DRONECAN) return; - UNUSED(pgnssAux); - // No useful information I think... Placeholder until after testing. lastVDOP = pgnssAux->vdop * 100; lastHDOP = pgnssAux->hdop * 100; - } #endif \ No newline at end of file From 4aa03ed1741c20d65a8737fc56b3a45b68e49ba1 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 13:49:16 -0700 Subject: [PATCH 19/48] dronecan: rate-limit protocol status check to 1Hz in NORMAL state MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit canardSTM32GetProtocolStatus() was called on every dronecanUpdate() invocation (~500Hz) to detect bus-off. Moved into the existing 1Hz task block — bus-off detection latency of up to 1s is acceptable. Adds LOG_DEBUG to report BusOff and ErrorPassive flags each second for bench diagnostics. --- src/main/drivers/dronecan/dronecan.c | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index bd9d579c3a7..e41ef75f3cf 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -469,12 +469,13 @@ void dronecanUpdate(timeUs_t currentTimeUs) next_1hz_service_at += 1000000ULL; process1HzTasks(currentTimeUs); processCanardTxQueue(); - } - canardSTM32GetProtocolStatus(&protocolStatus); - if(protocolStatus.BusOff != 0) { - dronecanState = STATE_DRONECAN_BUS_OFF; - busoffTimeUs = currentTimeUs; + canardSTM32GetProtocolStatus(&protocolStatus); + LOG_DEBUG(CAN, "CAN status: BusOff=%lu ErrorPassive=%lu", protocolStatus.BusOff, protocolStatus.ErrorPassive); + if (protocolStatus.BusOff != 0) { + dronecanState = STATE_DRONECAN_BUS_OFF; + busoffTimeUs = currentTimeUs; + } } break; From beef5b35db0af828b63ebc834bd5ba32f5534e8d Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:08:50 -0700 Subject: [PATCH 20/48] dronecan/f7: implement RecoverFromBusOff to clear sticky ESR.BOFF flag AutoBusOff=ENABLE handles the 128x11 recovery sequence automatically, but ESR.BOFF is a sticky read-only flag that is NOT cleared when hardware recovery completes. GetProtocolStatus() reads this flag, so the state machine was permanently stuck in STATE_DRONECAN_BUS_OFF after any bus-off event on F7 targets. Stop/Start re-enters init mode which clears ESR.BOFF, allowing recovery detection to work correctly. --- .../drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 371ee9e0f8a..b7915d98edf 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -399,6 +399,11 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ } void canardSTM32RecoverFromBusOff(void){ + // AutoBusOff=ENABLE handles the 128x11 recovery sequence automatically. + // Stop/Start re-enters init mode which clears the sticky ESR.BOFF flag + // so GetProtocolStatus() can detect recovery and return to NORMAL state. + HAL_CAN_Stop(&hcan1); + HAL_CAN_Start(&hcan1); } /* From cb04564c64ac15730644080cffa7a47d86729ba4 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:15:13 -0700 Subject: [PATCH 21/48] dronecan/h7: fix static_assert comment for PLL2M HSE divisibility check MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Comment incorrectly stated '25MHz' as a supported HSE value — 25MHz fails the assert. CMake always provides HSE_VALUE per-target via -DHSE_VALUE= so the stm32h7xx_hal_conf.h fallback of 25MHz is never used. Current targets use 8MHz (default) or 16MHz (KAKUTEH7WING). --- src/main/target/system_stm32h7xx.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index c55d3acd552..eaf88057cfb 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -500,6 +500,9 @@ void SystemClock_Config(void) #if defined(USE_SDCARD_SDIO) || defined(USE_DRONECAN) // PLL2M = HSE_VALUE / 1600000 pins the VCO input to exactly 1.6 MHz for any HSE. // With N=500: VCO=800 MHz, PLL2R/4=200 MHz (SDMMC), PLL2Q/10=80 MHz (FDCAN). + // HSE_VALUE must be an exact multiple of 1600000. CMake sets it per-target via -DHSE_VALUE=; + // current targets use 8MHz (÷5) and 16MHz (÷10). If adding a target with a non-multiple HSE, + // this assert will fire — choose a different VCO input frequency. STATIC_ASSERT(HSE_VALUE % 1600000 == 0, HSE_not_a_multiple_of_1600000); RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; RCC_PeriphClkInit.PLL2.PLL2N = 500; From c9533692d5a25646aa6a7cac63eab6f2a0653415 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:28:53 -0700 Subject: [PATCH 22/48] dronecan: rate-limit protocol status check in BUS_OFF state to 20ms cadence MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit GetProtocolStatus() was called every dronecanUpdate() cycle (~500Hz) in BUS_OFF state. Moved inside the 20ms recovery timer block so it runs at the same cadence as RecoverFromBusOff() — still detects recovery within 20ms but reduces MMIO reads from ~500/sec to ~50/sec. --- src/main/drivers/dronecan/dronecan.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index e41ef75f3cf..e4f40853db9 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -483,10 +483,10 @@ void dronecanUpdate(timeUs_t currentTimeUs) if(currentTimeUs > (busoffTimeUs + 20000)) { // Wait 20ms: worst-case 128x11 recovery is 11.264ms at 125kbps canardSTM32RecoverFromBusOff(); busoffTimeUs = currentTimeUs; - } - canardSTM32GetProtocolStatus(&protocolStatus); - if(protocolStatus.BusOff == 0) { - dronecanState = STATE_DRONECAN_NORMAL; + canardSTM32GetProtocolStatus(&protocolStatus); + if(protocolStatus.BusOff == 0) { + dronecanState = STATE_DRONECAN_NORMAL; + } } break; From fd56f93811494126b4f3ce5334b5d47930261228 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:31:02 -0700 Subject: [PATCH 23/48] =?UTF-8?q?dronecan/f7:=20revert=20RecoverFromBusOff?= =?UTF-8?q?=20HAL=5FCAN=5FStop/Start=20=E2=80=94=20causes=20lockup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit HAL_CAN_Stop/Start called from the scheduler context with CAN interrupts active caused a full FC lockup. Reverted to empty stub pending investigation of a safe mechanism to clear the sticky ESR.BOFF flag on F7. --- .../drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index b7915d98edf..2f3bc545d94 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -400,10 +400,9 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ void canardSTM32RecoverFromBusOff(void){ // AutoBusOff=ENABLE handles the 128x11 recovery sequence automatically. - // Stop/Start re-enters init mode which clears the sticky ESR.BOFF flag - // so GetProtocolStatus() can detect recovery and return to NORMAL state. - HAL_CAN_Stop(&hcan1); - HAL_CAN_Start(&hcan1); + // TODO: ESR.BOFF is a sticky flag not cleared by AutoBusOff recovery. + // HAL_CAN_Stop/Start would clear it but caused lockups on F7 when called + // from the scheduler context with CAN interrupts active. Needs investigation. } /* From 26b93787107f7dab62d0ded159480c1b6d0d0943 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:38:27 -0700 Subject: [PATCH 24/48] dronecan: only log CAN status when BusOff or ErrorPassive is non-zero Unconditional 1Hz LOG_DEBUG was flooding the bootlog with healthy status messages. Now only logs when an error condition is actually present. --- src/main/drivers/dronecan/dronecan.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index e4f40853db9..4bc8079283e 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -471,7 +471,9 @@ void dronecanUpdate(timeUs_t currentTimeUs) processCanardTxQueue(); canardSTM32GetProtocolStatus(&protocolStatus); - LOG_DEBUG(CAN, "CAN status: BusOff=%lu ErrorPassive=%lu", protocolStatus.BusOff, protocolStatus.ErrorPassive); + if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { + LOG_DEBUG(CAN, "CAN status: BusOff=%lu ErrorPassive=%lu", protocolStatus.BusOff, protocolStatus.ErrorPassive); + } if (protocolStatus.BusOff != 0) { dronecanState = STATE_DRONECAN_BUS_OFF; busoffTimeUs = currentTimeUs; From 9d244c33983437d3ed087b2d5891aee1e3f05b49 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:44:35 -0700 Subject: [PATCH 25/48] dronecan/f7: remove TX failure log spam MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit HAL_CAN_AddTxMessage returns non-OK when all mailboxes are busy — a normal transient condition at startup. The log was noise. Matches the H7 driver which already handles this path silently. --- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 2f3bc545d94..6ccbca40122 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -167,9 +167,7 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { return 1; } - LOG_DEBUG(CAN, "Failed at adding message with id: %lu to Tx Queue. Error: %lu", tx_frame->id, returnCode); - - // TX failed (FIFO full or other error) - return 0 to signal retry needed + // TX failed (mailboxes full or bus error) - return 0 to signal retry needed return 0; } From 858b1add0c3aaed2a1366133f0258c08a33f2686 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:50:17 -0700 Subject: [PATCH 26/48] dronecan/gps: guard GNSSAuxiliary DOP fields against NaN and overflow DroneCAN float16 optional fields encode NaN when unpopulated. Without a guard, NaN * 100 converts to 0 on Cortex-M (ARM VCVT saturation), permanently blocking the HDOP fallback path. Also passes values through gpsConstrainHDOP() to prevent uint16_t overflow for extreme DOP values. --- src/main/io/gps_dronecan.c | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/io/gps_dronecan.c b/src/main/io/gps_dronecan.c index 0c3acd20d77..c03125a7b97 100644 --- a/src/main/io/gps_dronecan.c +++ b/src/main/io/gps_dronecan.c @@ -181,7 +181,13 @@ void dronecanGPSReceiveGNSSFix2(const struct uavcan_equipment_gnss_Fix2 * pgnssF void dronecanGPSReceiveGNSSAuxiliary(const struct uavcan_equipment_gnss_Auxiliary * pgnssAux) { - lastVDOP = pgnssAux->vdop * 100; - lastHDOP = pgnssAux->hdop * 100; + // DroneCAN float16 optional fields encode NaN when unpopulated; guard before use. + // gpsConstrainHDOP clamps to 9999 preventing uint16_t overflow for extreme DOP values. + if (!isnan(pgnssAux->hdop)) { + lastHDOP = gpsConstrainHDOP((uint32_t)(pgnssAux->hdop * 100)); + } + if (!isnan(pgnssAux->vdop)) { + lastVDOP = gpsConstrainHDOP((uint32_t)(pgnssAux->vdop * 100)); + } } #endif \ No newline at end of file From c93570e2c61e4f85922a87fb01fb9cd47710555b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:54:19 -0700 Subject: [PATCH 27/48] =?UTF-8?q?dronecan/gps:=20remove=20lastVDOP=20?= =?UTF-8?q?=E2=80=94=20no=20vdop=20field=20in=20gpsSol=20and=20not=20EPV-c?= =?UTF-8?q?ompatible?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit gpsSolDRV has hdop but no vdop field. VDOP and EPV are not interchangeable (different units, conversion requires receiver UERE). lastVDOP was a dead store with no valid consumer. --- src/main/io/gps_dronecan.c | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/main/io/gps_dronecan.c b/src/main/io/gps_dronecan.c index c03125a7b97..07e595cd208 100644 --- a/src/main/io/gps_dronecan.c +++ b/src/main/io/gps_dronecan.c @@ -56,7 +56,6 @@ static bool newDataReady; static uint16_t lastHDOP = 9999; -static uint16_t lastVDOP = 9999; void gpsRestartDronecan(void) { @@ -186,8 +185,5 @@ void dronecanGPSReceiveGNSSAuxiliary(const struct uavcan_equipment_gnss_Auxiliar if (!isnan(pgnssAux->hdop)) { lastHDOP = gpsConstrainHDOP((uint32_t)(pgnssAux->hdop * 100)); } - if (!isnan(pgnssAux->vdop)) { - lastVDOP = gpsConstrainHDOP((uint32_t)(pgnssAux->vdop * 100)); - } } #endif \ No newline at end of file From 43aa5e80d3b90851e264a8ec8ce52eaaad308370 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:56:27 -0700 Subject: [PATCH 28/48] dronecan: add STATE_DRONECAN_COUNT sentinel and assert dronecanStateNames size MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Guards the CLI state name array against future enum additions — if a new state is added without updating the array, the build fails immediately. --- src/main/drivers/dronecan/dronecan.h | 3 ++- src/main/fc/cli.c | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/dronecan.h b/src/main/drivers/dronecan/dronecan.h index 9f53a570337..202011b0483 100644 --- a/src/main/drivers/dronecan/dronecan.h +++ b/src/main/drivers/dronecan/dronecan.h @@ -15,7 +15,8 @@ typedef enum { STATE_DRONECAN_INIT, STATE_DRONECAN_NORMAL, STATE_DRONECAN_BUS_OFF, - STATE_DRONECAN_FAILED + STATE_DRONECAN_FAILED, + STATE_DRONECAN_COUNT } dronecanState_e; #define DRONECAN_MAX_NODES 32 // Reasonably expected number of devices on the bus. If this is regularly hit, we could go higher but it consumes more ram. diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 99a854b35fd..ac55eb165ef 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4201,6 +4201,7 @@ static void cliStatus(char *cmdline) #ifdef USE_DRONECAN static const char * const dronecanStateNames[] = {"INIT", "NORMAL", "BUS_OFF", "FAILED"}; + STATIC_ASSERT(ARRAY_LENGTH(dronecanStateNames) == STATE_DRONECAN_COUNT, dronecanStateNames_size_mismatch); cliPrintLinef("DroneCAN: nodeID=%d, bitrate=%u kbps, status=%s, nodes=%d", dronecanConfig()->nodeID, (unsigned)dronecanGetBitrateKbps(), From 606c932d3b057b1a2f5eda7e9a141498912b38f2 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:58:14 -0700 Subject: [PATCH 29/48] dronecan: handle STATE_DRONECAN_COUNT in switch to satisfy -Werror=switch --- src/main/drivers/dronecan/dronecan.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 4bc8079283e..9d99a0c71a1 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -495,6 +495,9 @@ void dronecanUpdate(timeUs_t currentTimeUs) case STATE_DRONECAN_FAILED: break; + case STATE_DRONECAN_COUNT: + break; + } } From a8937d699f4e07d4806be31aaeb0c796e9b05755 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 17:14:51 -0700 Subject: [PATCH 30/48] dronecan: fix ARRAYLEN macro name in dronecanStateNames assert --- src/main/fc/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index ac55eb165ef..eb4454ac564 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4201,7 +4201,7 @@ static void cliStatus(char *cmdline) #ifdef USE_DRONECAN static const char * const dronecanStateNames[] = {"INIT", "NORMAL", "BUS_OFF", "FAILED"}; - STATIC_ASSERT(ARRAY_LENGTH(dronecanStateNames) == STATE_DRONECAN_COUNT, dronecanStateNames_size_mismatch); + STATIC_ASSERT(ARRAYLEN(dronecanStateNames) == STATE_DRONECAN_COUNT, dronecanStateNames_size_mismatch); cliPrintLinef("DroneCAN: nodeID=%d, bitrate=%u kbps, status=%s, nodes=%d", dronecanConfig()->nodeID, (unsigned)dronecanGetBitrateKbps(), From f17bb690bfb52a197973bff578e1e7636ae4e657 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 17:42:45 -0700 Subject: [PATCH 31/48] dronecan: clamp state index before dronecanStateNames lookup in CLI Guards against out-of-bounds read if dronecanState is ever corrupted to STATE_DRONECAN_COUNT or beyond. --- src/main/fc/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index eb4454ac564..d69e4671b37 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4205,7 +4205,7 @@ static void cliStatus(char *cmdline) cliPrintLinef("DroneCAN: nodeID=%d, bitrate=%u kbps, status=%s, nodes=%d", dronecanConfig()->nodeID, (unsigned)dronecanGetBitrateKbps(), - dronecanStateNames[dronecanGetState()], + dronecanStateNames[MIN(dronecanGetState(), STATE_DRONECAN_COUNT - 1)], dronecanGetNodeCount() ); #endif From 21cc6083b67cf467d451d4befdbe64db3150fe3e Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 17:22:45 -0700 Subject: [PATCH 32/48] dronecan/f7: document why RecoverFromBusOff is a no-op MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ABOM (CAN_MCR bit 6) is enabled in canardSTM32CAN1_Init. Per RM0410 ss40.7.6, with ABOM=1 the hardware manages the full bus-off recovery sequence automatically: after 128x11 recessive bits it cycles INRQ and clears ESR.BOFF without any software intervention required. Removes an incorrect TODO asserting ESR.BOFF is sticky — it is a hardware-managed status bit that clears when bus-off state is left. --- .../drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 6ccbca40122..d630e9ab0ef 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -397,10 +397,10 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ } void canardSTM32RecoverFromBusOff(void){ - // AutoBusOff=ENABLE handles the 128x11 recovery sequence automatically. - // TODO: ESR.BOFF is a sticky flag not cleared by AutoBusOff recovery. - // HAL_CAN_Stop/Start would clear it but caused lockups on F7 when called - // from the scheduler context with CAN interrupts active. Needs investigation. + // No-op: ABOM (CAN_MCR bit 6) is set in canardSTM32CAN1_Init, so hardware + // manages the full bus-off recovery sequence automatically. After 128x11 + // recessive bits, hardware cycles INRQ and clears ESR.BOFF without software + // intervention. See RM0410 ss40.7.6 and CAN_MCR.ABOM, CAN_ESR.BOFF. } /* From 25734bd27b9ac8a32d3f4fc454ca044ae75de361 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 20:25:06 -0700 Subject: [PATCH 33/48] dronecan: fix sign-compare in CLI state name clamp Cast both MIN() arguments to int to avoid -Werror=sign-compare between dronecanState_e (unsigned enum) and STATE_DRONECAN_COUNT - 1 (int). --- src/main/fc/cli.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index d69e4671b37..7f281a28a46 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4205,7 +4205,7 @@ static void cliStatus(char *cmdline) cliPrintLinef("DroneCAN: nodeID=%d, bitrate=%u kbps, status=%s, nodes=%d", dronecanConfig()->nodeID, (unsigned)dronecanGetBitrateKbps(), - dronecanStateNames[MIN(dronecanGetState(), STATE_DRONECAN_COUNT - 1)], + dronecanStateNames[MIN((int)dronecanGetState(), (int)STATE_DRONECAN_COUNT - 1)], dronecanGetNodeCount() ); #endif From ff85f781184e32610dd980b5c19425796c9ac7ea Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 20:28:27 -0700 Subject: [PATCH 34/48] dronecan: fix %lu format specifier for uint32_t fields clang treats uint32_t as unsigned int, not unsigned long. Use %u to match the actual type of BusOff and ErrorPassive in canardProtocolStatus_t. --- src/main/drivers/dronecan/dronecan.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 9d99a0c71a1..5994df1c300 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -472,7 +472,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) canardSTM32GetProtocolStatus(&protocolStatus); if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { - LOG_DEBUG(CAN, "CAN status: BusOff=%lu ErrorPassive=%lu", protocolStatus.BusOff, protocolStatus.ErrorPassive); + LOG_DEBUG(CAN, "CAN status: BusOff=%u ErrorPassive=%u", protocolStatus.BusOff, protocolStatus.ErrorPassive); } if (protocolStatus.BusOff != 0) { dronecanState = STATE_DRONECAN_BUS_OFF; From 354df59ef7be8ff5dc56f5f6dfc58e9e9d42436c Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 22:24:47 -0700 Subject: [PATCH 35/48] fix: use PRIu32 for uint32_t format specifiers in dronecan LOG_DEBUG --- src/main/drivers/dronecan/dronecan.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 5994df1c300..e79144a8c84 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -472,7 +472,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) canardSTM32GetProtocolStatus(&protocolStatus); if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { - LOG_DEBUG(CAN, "CAN status: BusOff=%u ErrorPassive=%u", protocolStatus.BusOff, protocolStatus.ErrorPassive); + LOG_DEBUG(CAN, "CAN status: BusOff=%" PRIu32 " ErrorPassive=%" PRIu32, protocolStatus.BusOff, protocolStatus.ErrorPassive); } if (protocolStatus.BusOff != 0) { dronecanState = STATE_DRONECAN_BUS_OFF; From ebb39c91123d8c7c8d8926ae34a4a4299d2ee7a3 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sun, 31 May 2026 20:04:59 -0700 Subject: [PATCH 36/48] fix(dronecan): send elapsed ms since last seen in MSP2_INAV_DRONECAN_NODES Previously last_seen_ms was the raw millis() timestamp when the node was last heard from, which equals FC uptime for active nodes. Configurators had no way to compute elapsed time without knowing current FC millis(). Now sends millis() - last_seen_ms so the field means "ms since this node was last heard from". Unsigned subtraction handles millis() wraparound correctly. --- src/main/fc/fc_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index e5cfe7e81e8..2053f123a8c 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1899,7 +1899,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF .nodeID = node->nodeID, .health = node->health, .mode = node->mode, - .last_seen_ms = node->last_seen_ms, + .last_seen_ms = millis() - node->last_seen_ms, }, sizeof(dronecanNodeStatus_t)); } } From 69d565d2b0519884f4754edb8b5949f582734767 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sun, 31 May 2026 20:41:17 -0700 Subject: [PATCH 37/48] fix(dronecan): send elapsed ms since last seen in MSP2_INAV_DRONECAN_NODE_INFO Apply the same fix as MSP2_INAV_DRONECAN_NODES: send millis() - last_seen_ms so the field means elapsed time since last heard from the node. --- src/main/fc/fc_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 2053f123a8c..9da0b461562 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4608,7 +4608,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu sbufWriteU8(dst, node->mode); sbufWriteU32(dst, node->uptime_sec); sbufWriteU16(dst, node->vendor_status_code); - sbufWriteU32(dst, node->last_seen_ms); + sbufWriteU32(dst, millis() - node->last_seen_ms); sbufWriteU8(dst, node->name_len); sbufWriteDataSafe(dst, node->name, 32); found = true; From 1532585c2819bbaafba15507a3c051f67dd4bd9c Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 11 Jun 2026 21:02:37 -0700 Subject: [PATCH 38/48] dronecan/h7: TX queue mode, depth 3, ISR pump, NVIC masking MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Switch FDCAN from FIFO to Queue mode so hardware transmits highest-priority frame first, matching libcanard's scheduler. Reduce staging depth 32→3 so libcanard's queue remains authoritative between poll cycles. Add HAL_FDCAN_TxBufferCompleteCallback ISR pump to refill the hardware slot immediately on TX complete. Wrap all canardBroadcast, canardRequestOrRespond, and canardCleanupStaleTransfers call sites with NVIC_DisableIRQ/EnableIRQ on FDCAN1_IT1 to prevent races between the ISR and main task on libcanard's queue. Masking helpers are no-ops on non-H7 targets. --- src/main/drivers/dronecan/dronecan.c | 40 ++++++++++++++++--- .../libcanard/canard_stm32h7xx_driver.c | 11 ++++- 2 files changed, 43 insertions(+), 8 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index e79144a8c84..31daec2a13f 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -42,6 +42,14 @@ static dronecanState_e dronecanState = STATE_DRONECAN_INIT; static uint8_t activeNodeCount = 0; static dronecanNodeInfo_t nodeTable[DRONECAN_MAX_NODES]; +#if defined(STM32H7) +static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(FDCAN1_IT1_IRQn); } +static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(FDCAN1_IT1_IRQn); } +#else +static inline void dronecanMaskTxISR(void) {} +static inline void dronecanUnmaskTxISR(void) {} +#endif + // NOTE: All canard handlers and senders are based on this reference: https://dronecan.github.io/Specification/7._List_of_standard_data_types/ // Alternatively, you can look at the corresponding generated header file in the dsdlc_generated folder @@ -173,6 +181,7 @@ void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + dronecanMaskTxISR(); canardRequestOrRespond(ins, transfer->source_node_id, UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, @@ -182,6 +191,7 @@ void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { CanardResponse, &buffer[0], total_size); + dronecanUnmaskTxISR(); } // Canard Senders @@ -214,6 +224,7 @@ void send_NodeStatus(void) { // loss static uint8_t transfer_id; + dronecanMaskTxISR(); canardBroadcast(&canard, UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, UAVCAN_PROTOCOL_NODESTATUS_ID, @@ -221,7 +232,8 @@ void send_NodeStatus(void) { CANARD_TRANSFER_PRIORITY_LOW, buffer, len); - // PrintCanStatus(); + dronecanUnmaskTxISR(); + } // Canard Util @@ -341,7 +353,6 @@ void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { } } - void processCanardTxQueue(void) { // Transmitting for (const CanardCANFrame *tx_frame ; (tx_frame = canardPeekTxQueue(&canard)) != NULL;) @@ -358,9 +369,24 @@ void processCanardTxQueue(void) { break; } } - } +static void processCanardTxQueueSafe(void) { + dronecanMaskTxISR(); + processCanardTxQueue(); + dronecanUnmaskTxISR(); +} + +#if defined(STM32H7) +void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes) +{ + UNUSED(hfdcan); + UNUSED(BufferIndexes); + processCanardTxQueue(); +} +#endif + + /* This function is called at 1 Hz rate from the main loop. */ @@ -369,7 +395,9 @@ void process1HzTasks(timeUs_t timestamp_usec) /* Purge transfers that are no longer transmitted. This can free up some memory */ + dronecanMaskTxISR(); canardCleanupStaleTransfers(&canard, timestamp_usec); + dronecanUnmaskTxISR(); /* Transmit the node status message @@ -445,7 +473,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) break; case STATE_DRONECAN_NORMAL: - processCanardTxQueue(); + processCanardTxQueueSafe(); for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--) { @@ -462,13 +490,13 @@ void dronecanUpdate(timeUs_t currentTimeUs) } // Drain any TX frames queued by RX handlers (e.g. GetNodeInfo responses) // in the same task cycle so multi-frame transfers complete before timeout. - processCanardTxQueue(); + processCanardTxQueueSafe(); if (currentTimeUs >= next_1hz_service_at) { next_1hz_service_at += 1000000ULL; process1HzTasks(currentTimeUs); - processCanardTxQueue(); + processCanardTxQueueSafe(); canardSTM32GetProtocolStatus(&protocolStatus); if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 74f984edf2d..d0ecdd8ed2d 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -175,10 +175,10 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8; hfdcan1.Init.StdFiltersNbr = 0; hfdcan1.Init.ExtFiltersNbr = 1; - hfdcan1.Init.TxFifoQueueElmtsNbr = 32; + hfdcan1.Init.TxFifoQueueElmtsNbr = 3; hfdcan1.Init.TxEventsNbr = 0; hfdcan1.Init.TxBuffersNbr = 0; - hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; + hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_QUEUE_OPERATION; hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8; canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode @@ -201,6 +201,13 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) LOG_ERROR(CAN, "Failed to Start"); return -CANARD_ERROR_INTERNAL; } + + if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_TX_COMPLETE, + FDCAN_TX_BUFFER0 | FDCAN_TX_BUFFER1 | FDCAN_TX_BUFFER2)) { + LOG_ERROR(CAN, "Failed to activate interrupt notification"); + return -CANARD_ERROR_INTERNAL; + } + return CANARD_OK; } From b330a8a77787c6803c9bab8dc74d844d007f2a3a Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 11 Jun 2026 21:38:04 -0700 Subject: [PATCH 39/48] dronecan: F7 ISR-driven TX, NVIC masking, TEC/REC/LEC counters, cliDronecan Phase 2 of the combined DroneCAN driver rework (folds in #11560 content): F7 bxCAN ISR-driven TX refill: - Add NVIC_PRIO_CAN=4 to nvic.h (shared by H7 and F7) - Enable CAN_IT_TX_MAILBOX_EMPTY and CAN1_TX_IRQn at NVIC_PRIO_CAN - Add HAL_CAN_TxMailbox{0,1,2}CompleteCallback ISR pumps in dronecan.c - Wire dronecanMaskTxISR/UnmaskTxISR to NVIC_DisableIRQ/EnableIRQ(CAN1_TX_IRQn) - Add #else branch for SITL/AT32 (was missing, would break SITL build) TEC/REC/LEC error counters: - Extend canardProtocolStatus_t with tec, rec, lec fields - F7: populate from ESR register (bits 23:16, 31:24, 6:4) - H7: populate from ECR register (bits 22:16, 14:8) + PSR.LastErrorCode Typo fix: canardSTM32Recieve -> canardSTM32Receive across all drivers and call sites Other: - Add canardSTM32GetTxQueueFillLevel() to all three drivers (returns 0; no SW queue) - Make canard and memory_pool static in dronecan.c - Add cliDronecan CLI command showing bus health (BusOff, ErrorPassive, TEC, REC, LEC, fill levels) --- src/main/drivers/dronecan/dronecan.c | 14 +++++++--- .../dronecan/libcanard/canard_sitl_driver.c | 15 +++++------ .../dronecan/libcanard/canard_stm32_driver.h | 6 ++++- .../libcanard/canard_stm32f7xx_driver.c | 26 ++++++++++++++++--- .../libcanard/canard_stm32h7xx_driver.c | 15 ++++++++--- src/main/drivers/nvic.h | 1 + src/main/fc/cli.c | 26 +++++++++++++++++++ 7 files changed, 83 insertions(+), 20 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 31daec2a13f..4c6c3865bf5 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -27,8 +27,8 @@ /* Private variables ---------------------------------------------------------*/ -CanardInstance canard; -uint8_t memory_pool[1024]; +static CanardInstance canard; +static uint8_t memory_pool[1024]; static struct uavcan_protocol_NodeStatus node_status; PG_REGISTER_WITH_RESET_TEMPLATE(dronecanConfig_t, dronecanConfig, PG_DRONECAN_CONFIG, 0); @@ -45,6 +45,9 @@ static dronecanNodeInfo_t nodeTable[DRONECAN_MAX_NODES]; #if defined(STM32H7) static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(FDCAN1_IT1_IRQn); } static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(FDCAN1_IT1_IRQn); } +#elif defined(STM32F7) +static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(CAN1_TX_IRQn); } +static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(CAN1_TX_IRQn); } #else static inline void dronecanMaskTxISR(void) {} static inline void dronecanUnmaskTxISR(void) {} @@ -385,6 +388,11 @@ void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t Bu processCanardTxQueue(); } #endif +#if defined(STM32F7) +void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +#endif /* @@ -478,7 +486,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--) { timestamp = millis() * 1000ULL; - rx_res = canardSTM32Recieve(&rx_frame); + rx_res = canardSTM32Receive(&rx_frame); if (rx_res < 0) { LOG_DEBUG(CAN, "Receive error %d", rx_res); diff --git a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c index 8743e779dea..2f70faa459f 100644 --- a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c @@ -106,8 +106,7 @@ static int16_t sitlCANTransmitStub(const CanardCANFrame* const tx_frame) { } static void sitlCANGetStatsStub(canardProtocolStatus_t *pProtocolStat) { - pProtocolStat->BusOff = 0; - pProtocolStat->ErrorPassive = 0; + memset(pProtocolStat, 0, sizeof(*pProtocolStat)); } #ifdef __linux__ @@ -267,11 +266,7 @@ static int16_t sitlCANTransmitSocketCAN(const CanardCANFrame* const tx_frame) { * @param pProtocolStat Pointer to status structure to fill */ static void sitlCANGetStatsSocketCAN(canardProtocolStatus_t *pProtocolStat) { - // SocketCAN doesn't expose bus-off/error-passive directly - // We could check interface flags via netlink, but for SITL testing - // we assume the virtual CAN is always healthy - pProtocolStat->BusOff = 0; - pProtocolStat->ErrorPassive = 0; + memset(pProtocolStat, 0, sizeof(*pProtocolStat)); } #endif // __linux__ @@ -280,7 +275,7 @@ static void sitlCANGetStatsSocketCAN(canardProtocolStatus_t *pProtocolStat) { * @param rx_frame Pointer to frame structure to fill * @retval 0 if no frame available, 1 if frame received, negative on error */ -int16_t canardSTM32Recieve(CanardCANFrame *const rx_frame) { +int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { if (rx_frame == NULL) { return -CANARD_ERROR_INVALID_ARGUMENT; } @@ -357,6 +352,10 @@ int32_t canardSTM32GetRxFifoFillLevel(void) { return 0; } +int32_t canardSTM32GetTxQueueFillLevel(void) { + return 0; +} + /** * @brief Recover from bus-off condition */ diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h b/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h index fe70cddf1d9..c5fd6a5133e 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h +++ b/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h @@ -12,15 +12,19 @@ typedef struct { uint32_t BusOff; uint32_t ErrorPassive; + uint8_t tec; + uint8_t rec; + uint8_t lec; } canardProtocolStatus_t; #ifdef USE_DRONECAN int16_t canardSTM32CAN1_Init(uint32_t bitrate); -int16_t canardSTM32Recieve(CanardCANFrame *const rx_frame); +int16_t canardSTM32Receive(CanardCANFrame *const rx_frame); int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame); void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat); +int32_t canardSTM32GetTxQueueFillLevel(void); int32_t canardSTM32GetRxFifoFillLevel(void); void canardSTM32RecoverFromBusOff(void); void canardSTM32GetUniqueID(uint8_t id[16]); diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index d630e9ab0ef..0e0e0026392 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -8,6 +8,7 @@ #include "common/log.h" #include "common/time.h" #include "drivers/io.h" +#include "drivers/nvic.h" #include "canard.h" #include "canard_stm32_driver.h" @@ -93,7 +94,7 @@ uint8_t rxBufferNumMessages(struct RxBuffer_t *rxBuf) { * stored. * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode */ -int16_t canardSTM32Recieve(CanardCANFrame *const rx_frame) { +int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { RxFrame_t canRxFrame; if (rx_frame == NULL) { @@ -240,8 +241,14 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) // Enable interrupt only after all initialization succeeds // (if any previous step failed, we return early without enabling IRQ) - HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 0, 0); + HAL_NVIC_SetPriority(CAN1_RX0_IRQn, NVIC_PRIO_CAN, 0); HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); + if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) { + LOG_ERROR(CAN, "Failed to activate TX interrupt"); + return -CANARD_ERROR_INTERNAL; + } + HAL_NVIC_SetPriority(CAN1_TX_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); return CANARD_OK; } @@ -387,9 +394,16 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ - - pProtocolStat->BusOff = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_BOF); + uint32_t esr = hcan1.Instance->ESR; + pProtocolStat->BusOff = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_BOF); pProtocolStat->ErrorPassive = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_EPV); + pProtocolStat->tec = (uint8_t)((esr >> 16) & 0xFF); + pProtocolStat->rec = (uint8_t)((esr >> 24) & 0xFF); + pProtocolStat->lec = (uint8_t)((esr >> 4) & 0x07); +} + +int32_t canardSTM32GetTxQueueFillLevel(void){ + return 0; } int32_t canardSTM32GetRxFifoFillLevel(void){ @@ -420,6 +434,10 @@ void CAN1_RX0_IRQHandler(void) { HAL_CAN_IRQHandler(&hcan1); } +void CAN1_TX_IRQHandler(void) { + HAL_CAN_IRQHandler(&hcan1); +} + void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { RxFrame_t frame; if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &frame.header, frame.data) == HAL_OK) { diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index d0ecdd8ed2d..5927c304ecd 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -40,7 +40,7 @@ static FDCAN_HandleTypeDef hfdcan1; * stored. * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode */ -int16_t canardSTM32Recieve(CanardCANFrame *const rx_frame) { +int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { if (rx_frame == NULL) { return -CANARD_ERROR_INVALID_ARGUMENT; } @@ -351,11 +351,18 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ - FDCAN_ProtocolStatusTypeDef protocolStatus = {}; - + FDCAN_ProtocolStatusTypeDef protocolStatus = {}; HAL_FDCAN_GetProtocolStatus(&hfdcan1, &protocolStatus); - pProtocolStat->BusOff = protocolStatus.BusOff; + pProtocolStat->BusOff = protocolStatus.BusOff; pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; + uint32_t ecr = hfdcan1.Instance->ECR; + pProtocolStat->tec = (uint8_t)((ecr >> 16) & 0x7F); + pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); + pProtocolStat->lec = (uint8_t)(protocolStatus.LastErrorCode & 0x07); +} + +int32_t canardSTM32GetTxQueueFillLevel(void){ + return 0; } int32_t canardSTM32GetRxFifoFillLevel(void){ diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index cb484937d3d..8ff16cd2998 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -12,6 +12,7 @@ #define NVIC_PRIO_TIMER 3 #define NVIC_PRIO_TIMER_DMA 3 #define NVIC_PRIO_SDIO 3 +#define NVIC_PRIO_CAN 4 #define NVIC_PRIO_USB 5 #define NVIC_PRIO_SERIALUART 5 #define NVIC_PRIO_VCP 7 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 7f281a28a46..97e465d1231 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -125,6 +125,7 @@ bool cliMode = false; #include "sensors/temperature.h" #ifdef USE_DRONECAN #include "drivers/dronecan/dronecan.h" +#include "drivers/dronecan/libcanard/canard_stm32_driver.h" #endif #ifdef USE_ESC_SENSOR #include "sensors/esc_sensor.h" @@ -4694,6 +4695,28 @@ static void printConfig(const char *cmdline, bool doDiff) restoreConfigs(); } +#ifdef USE_DRONECAN +static void cliDronecan(char *cmdline) +{ + UNUSED(cmdline); + static const char * const lecNames[] = { + "None", "Stuff", "Form", "ACK", "BitR", "BitD", "CRC", "SW" + }; + canardProtocolStatus_t stat; + canardSTM32GetProtocolStatus(&stat); + int32_t txFill = canardSTM32GetTxQueueFillLevel(); + int32_t rxFill = canardSTM32GetRxFifoFillLevel(); + cliPrintLine("DroneCAN CAN peripheral status:"); + cliPrintLinef(" BusOff: %s", stat.BusOff ? "YES" : "no"); + cliPrintLinef(" ErrorPassive: %s", stat.ErrorPassive ? "YES" : "no"); + cliPrintLinef(" TEC: %u", (unsigned)stat.tec); + cliPrintLinef(" REC: %u", (unsigned)stat.rec); + cliPrintLinef(" LEC: %s (%u)", lecNames[stat.lec & 0x7], (unsigned)stat.lec); + cliPrintLinef(" TX queue: %ld", (long)txFill); + cliPrintLinef(" RX buffer: %ld", (long)rxFill); +} +#endif + static void cliDump(char *cmdline) { printConfig(cmdline, false); @@ -4939,6 +4962,9 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu), CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|battery_profile|control_profile|mixer_profile|rates|all] {showdefaults}", cliDiff), +#ifdef USE_DRONECAN + CLI_COMMAND_DEF("dronecan", "show DroneCAN CAN peripheral debug status", NULL, cliDronecan), +#endif CLI_COMMAND_DEF("dump", "dump configuration", "[master|battery_profile|control_profile|mixer_profile|rates|all] {showdefaults}", cliDump), #ifdef USE_RX_ELERES From ddbe1874c77dcfbb8ac62c93391b00cf1f1a00e0 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 11 Jun 2026 22:48:02 -0700 Subject: [PATCH 40/48] dronecan: fix H7 ISR pump, ECR TEC field, narrow TX mask window Fix H7 ISR pump (was completely non-functional): - FDCAN_IT_TX_COMPLETE routes to LINE0 by default (ILS=0); enable FDCAN1_IT0_IRQn at NVIC_PRIO_CAN and add FDCAN1_IT0_IRQHandler - Change dronecanMaskTxISR from FDCAN1_IT1_IRQn to FDCAN1_IT0_IRQn Fix H7 TEC extraction from ECR register: - ECR[7:0]=TEC, ECR[14:8]=REC, ECR[23:16]=CEL (not TEC) - Previous code read CEL and labelled it tec Narrow ISR mask window in processCanardTxQueueSafe: - Mask only covers canardPeekTxQueue/canardPopTxQueue (linked-list ops) - HAL transmit call now runs with ISR unmasked - Re-peek after transmit to detect if ISR already popped the frame F7 RxBuffer ISR safety: - writeIndex/readIndex now volatile to prevent compiler caching - Remove unused file-scope rxMsg variable - rxBufferPushFrame/PopFrame now int8_t and static - Log warning on RX buffer full instead of silently dropping Remove redundant lec & 0x7 mask in cliDronecan (already masked at population) --- src/main/drivers/dronecan/dronecan.c | 36 +++++++++++++++---- .../libcanard/canard_stm32f7xx_driver.c | 13 +++---- .../libcanard/canard_stm32h7xx_driver.c | 15 ++++++-- src/main/fc/cli.c | 2 +- 4 files changed, 50 insertions(+), 16 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 4c6c3865bf5..00644c5fc24 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -43,8 +43,8 @@ static uint8_t activeNodeCount = 0; static dronecanNodeInfo_t nodeTable[DRONECAN_MAX_NODES]; #if defined(STM32H7) -static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(FDCAN1_IT1_IRQn); } -static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(FDCAN1_IT1_IRQn); } +static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(FDCAN1_IT0_IRQn); } +static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(FDCAN1_IT0_IRQn); } #elif defined(STM32F7) static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(CAN1_TX_IRQn); } static inline void dronecanUnmaskTxISR(void) { NVIC_EnableIRQ(CAN1_TX_IRQn); } @@ -375,10 +375,34 @@ void processCanardTxQueue(void) { } static void processCanardTxQueueSafe(void) { - dronecanMaskTxISR(); - processCanardTxQueue(); - dronecanUnmaskTxISR(); -} + for (;;) { + // Mask only for the linked-list peek — not for the HAL transmit call + dronecanMaskTxISR(); + const CanardCANFrame *tx_frame = canardPeekTxQueue(&canard); + if (tx_frame == NULL) { + dronecanUnmaskTxISR(); + break; + } + const CanardCANFrame frame_copy = *tx_frame; + dronecanUnmaskTxISR(); + + const int16_t tx_res = canardSTM32Transmit(&frame_copy); + if (tx_res == 0) { + break; // HW TX full, ISR will refill when a slot opens + } + + // Re-mask to pop. If the ISR fired during the transmit call and already + // popped this frame, peek will return a different pointer — skip the pop. + dronecanMaskTxISR(); + if (canardPeekTxQueue(&canard) == tx_frame) { + if (tx_res < 0) { + LOG_DEBUG(CAN, "Transmit error %d", tx_res); + } + canardPopTxQueue(&canard); + } + dronecanUnmaskTxISR(); + } +} #if defined(STM32H7) void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 0e0e0026392..52c28df7a5d 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -34,8 +34,8 @@ typedef struct { } RxFrame_t; static struct RxBuffer_t { - uint8_t writeIndex; - uint8_t readIndex; + volatile uint8_t writeIndex; + volatile uint8_t readIndex; RxFrame_t rxMsg[RX_BUFFER_SIZE]; } RxBuffer; @@ -43,9 +43,8 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi static void canardSTM32GPIO_Init(void); static CAN_HandleTypeDef hcan1; -RxFrame_t rxMsg; -uint8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { +static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { uint8_t next; RxFrame_t *pCurrentRxMsg; @@ -63,7 +62,7 @@ uint8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { return 0; } -uint8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { +static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { uint8_t next; RxFrame_t *pCurrentRxMsg; @@ -441,6 +440,8 @@ void CAN1_TX_IRQHandler(void) { void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { RxFrame_t frame; if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &frame.header, frame.data) == HAL_OK) { - rxBufferPushFrame(&RxBuffer, &frame); + if (rxBufferPushFrame(&RxBuffer, &frame) != 0) { + LOG_WARNING(CAN, "RX buffer full, frame dropped"); + } } } \ No newline at end of file diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 5927c304ecd..617fa481e69 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -8,6 +8,7 @@ #include "common/log.h" #include "common/time.h" #include "drivers/io.h" +#include "drivers/nvic.h" #include "canard.h" #include "canard_stm32_driver.h" @@ -203,11 +204,15 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) } if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_TX_COMPLETE, - FDCAN_TX_BUFFER0 | FDCAN_TX_BUFFER1 | FDCAN_TX_BUFFER2)) { + FDCAN_TX_BUFFER0 | FDCAN_TX_BUFFER1 | FDCAN_TX_BUFFER2) != HAL_OK) { /* Must match TxFifoQueueElmtsNbr = 3 */ LOG_ERROR(CAN, "Failed to activate interrupt notification"); return -CANARD_ERROR_INTERNAL; } + /* FDCAN_IT_TX_COMPLETE routes to LINE0 by default (ILS resets to 0) */ + HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn); + return CANARD_OK; } @@ -356,8 +361,8 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ pProtocolStat->BusOff = protocolStatus.BusOff; pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; uint32_t ecr = hfdcan1.Instance->ECR; - pProtocolStat->tec = (uint8_t)((ecr >> 16) & 0x7F); - pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); + pProtocolStat->tec = (uint8_t)(ecr & 0xFF); /* ECR[7:0] */ + pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); /* ECR[14:8] */ pProtocolStat->lec = (uint8_t)(protocolStatus.LastErrorCode & 0x07); } @@ -385,4 +390,8 @@ void canardSTM32GetUniqueID(uint8_t id[16]) { HALUniqueIDs[1] = HAL_GetUIDw1(); HALUniqueIDs[2] = HAL_GetUIDw2(); memcpy(id, HALUniqueIDs, 12); +} + +void FDCAN1_IT0_IRQHandler(void) { + HAL_FDCAN_IRQHandler(&hfdcan1); } \ No newline at end of file diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 97e465d1231..593ed5dd1cd 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4711,7 +4711,7 @@ static void cliDronecan(char *cmdline) cliPrintLinef(" ErrorPassive: %s", stat.ErrorPassive ? "YES" : "no"); cliPrintLinef(" TEC: %u", (unsigned)stat.tec); cliPrintLinef(" REC: %u", (unsigned)stat.rec); - cliPrintLinef(" LEC: %s (%u)", lecNames[stat.lec & 0x7], (unsigned)stat.lec); + cliPrintLinef(" LEC: %s (%u)", lecNames[stat.lec], (unsigned)stat.lec); cliPrintLinef(" TX queue: %ld", (long)txFill); cliPrintLinef(" RX buffer: %ld", (long)rxFill); } From 3184173e96287c222caacf6a8510fd09274c7407 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 06:56:20 -0700 Subject: [PATCH 41/48] dronecan: reorder driver files to public API before private helpers Move public canardSTM32* functions above static helpers in H7 and F7 drivers. Move dronecanInit/Update/Get* to the top of dronecan.c with forward declarations for internal callbacks. Mark rxBufferNumMessages static in F7 driver. Add ISR-context warning comment to processCanardTxQueue. --- src/main/drivers/dronecan/dronecan.c | 748 +++++++++--------- .../libcanard/canard_stm32f7xx_driver.c | 306 +++---- .../libcanard/canard_stm32h7xx_driver.c | 239 +++--- 3 files changed, 661 insertions(+), 632 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 00644c5fc24..5daa3a359f6 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -53,151 +53,248 @@ static inline void dronecanMaskTxISR(void) {} static inline void dronecanUnmaskTxISR(void) {} #endif -// NOTE: All canard handlers and senders are based on this reference: https://dronecan.github.io/Specification/7._List_of_standard_data_types/ -// Alternatively, you can look at the corresponding generated header file in the dsdlc_generated folder +/* Forward declarations ------------------------------------------------------*/ -// Canard Handlers ( Many have code copied from libcanard esc_node example: https://github.com/dronecan/libcanard/blob/master/examples/ESCNode/esc_node.c ) +static void processCanardTxQueueSafe(void); +static void process1HzTasks(timeUs_t timestamp_usec); +bool shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, CanardTransferType transfer_type, uint8_t source_node_id); +void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer); -void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - struct uavcan_protocol_NodeStatus nodeStatus; +// ---- Public API ------------------------------------------------------------- - if (uavcan_protocol_NodeStatus_decode(transfer, &nodeStatus)) { - LOG_DEBUG(CAN, "NodeStatus decode failed"); - return; - } +void dronecanInit(void) +{ + uint32_t bitrate = 500000; // At least define 500000 - uint8_t nodeId = transfer->source_node_id; - for (uint8_t i = 0; i < activeNodeCount; i++) { - if (nodeTable[i].nodeID == nodeId) { - // update health, mode, uptime, vendor_status_code, last_seen_ms - nodeTable[i].health = nodeStatus.health; - nodeTable[i].mode = nodeStatus.mode; - nodeTable[i].uptime_sec = nodeStatus.uptime_sec; - nodeTable[i].vendor_status_code = nodeStatus.vendor_specific_status_code; - nodeTable[i].last_seen_ms = millis(); - return; - } - } - // new node - if (activeNodeCount < DRONECAN_MAX_NODES) { - nodeTable[activeNodeCount].nodeID = nodeId; - nodeTable[activeNodeCount].health = nodeStatus.health; - nodeTable[activeNodeCount].mode = nodeStatus.mode; - nodeTable[activeNodeCount].uptime_sec = nodeStatus.uptime_sec; - nodeTable[activeNodeCount].vendor_status_code = nodeStatus.vendor_specific_status_code; - nodeTable[activeNodeCount].name_len = 0; - nodeTable[activeNodeCount].name[0] = 0; - nodeTable[activeNodeCount].last_seen_ms = millis(); - activeNodeCount++; + switch (dronecanConfig()->bitRateKbps){ + case DRONECAN_BITRATE_125KBPS: + bitrate = 125000; + break; + + case DRONECAN_BITRATE_250KBPS: + bitrate = 250000; + break; + + case DRONECAN_BITRATE_500KBPS: + bitrate = 500000; + break; + + case DRONECAN_BITRATE_1000KBPS: + bitrate = 1000000; + break; + + case DRONECAN_BITRATE_COUNT: + LOG_ERROR(SYSTEM, "Undefined bitrate set in configuration. 500kbps selected"); + bitrate = 500000; + break; } + if(canardSTM32CAN1_Init(bitrate) != CANARD_OK) + { + LOG_ERROR(CAN, "Unable to initialize the CAN peripheral"); + dronecanState = STATE_DRONECAN_FAILED; + return; + } + /* + Initializing the Libcanard instance. + */ + canardInit(&canard, + memory_pool, + sizeof(memory_pool), + onTransferReceived, + shouldAcceptTransfer, + NULL); + // Could use DNA (Dynamic Node Allocation) by following example in esc_node.c but that requires a lot of setup and I'm not too sure of what advantage it brings + // Instead, set a different NODE_ID for each device on the CAN bus by configuring node_settings + if (dronecanConfig()->nodeID > 0) { + canardSetLocalNodeID(&canard, dronecanConfig()->nodeID); + } else { + LOG_DEBUG(CAN, "Node ID is 0, this node is anonymous and can't transmit most messages. Please update this in config"); + } } -void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - if (gpsConfig()->provider != GPS_DRONECAN) return; - struct uavcan_equipment_gnss_Auxiliary gnssAuxiliary; +void dronecanUpdate(timeUs_t currentTimeUs) +{ + static timeUs_t next_1hz_service_at = 0; + static timeUs_t busoffTimeUs = 0; + CanardCANFrame rx_frame; + int numMessagesToProcess = 0; + canardProtocolStatus_t protocolStatus = {}; + uint64_t timestamp; + int16_t rx_res; - if (uavcan_equipment_gnss_Auxiliary_decode(transfer, &gnssAuxiliary)) { - LOG_DEBUG(CAN, "GNSSAuxiliary decode failed"); - return; - } - dronecanGPSReceiveGNSSAuxiliary(&gnssAuxiliary); -} + switch(dronecanState) { + case STATE_DRONECAN_INIT: + next_1hz_service_at = currentTimeUs + 1000000ULL; // First 1Hz tick in 1 second + dronecanState = STATE_DRONECAN_NORMAL; + break; -void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - if (gpsConfig()->provider != GPS_DRONECAN) return; - struct uavcan_equipment_gnss_Fix gnssFix; + case STATE_DRONECAN_NORMAL: + processCanardTxQueueSafe(); - if (uavcan_equipment_gnss_Fix_decode(transfer, &gnssFix)) { - LOG_DEBUG(CAN, "GNSSFix decode failed"); - return; - } - dronecanGPSReceiveGNSSFix(&gnssFix); -} + for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--) + { + timestamp = millis() * 1000ULL; + rx_res = canardSTM32Receive(&rx_frame); -void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - if (gpsConfig()->provider != GPS_DRONECAN) return; - struct uavcan_equipment_gnss_Fix2 gnssFix2; + if (rx_res < 0) { + LOG_DEBUG(CAN, "Receive error %d", rx_res); + } + else if (rx_res > 0) // Success - process the frame + { + canardHandleRxFrame(&canard, &rx_frame, timestamp); + } + } + // Drain any TX frames queued by RX handlers (e.g. GetNodeInfo responses) + // in the same task cycle so multi-frame transfers complete before timeout. + processCanardTxQueueSafe(); + + if (currentTimeUs >= next_1hz_service_at) + { + next_1hz_service_at += 1000000ULL; + process1HzTasks(currentTimeUs); + processCanardTxQueueSafe(); + + canardSTM32GetProtocolStatus(&protocolStatus); + if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { + LOG_DEBUG(CAN, "CAN status: BusOff=%" PRIu32 " ErrorPassive=%" PRIu32, protocolStatus.BusOff, protocolStatus.ErrorPassive); + } + if (protocolStatus.BusOff != 0) { + dronecanState = STATE_DRONECAN_BUS_OFF; + busoffTimeUs = currentTimeUs; + } + } + break; + + case STATE_DRONECAN_BUS_OFF: + if(currentTimeUs > (busoffTimeUs + 20000)) { // Wait 20ms: worst-case 128x11 recovery is 11.264ms at 125kbps + canardSTM32RecoverFromBusOff(); + busoffTimeUs = currentTimeUs; + canardSTM32GetProtocolStatus(&protocolStatus); + if(protocolStatus.BusOff == 0) { + dronecanState = STATE_DRONECAN_NORMAL; + } + } + break; + + case STATE_DRONECAN_FAILED: + break; + + case STATE_DRONECAN_COUNT: + break; + + } - if (uavcan_equipment_gnss_Fix2_decode(transfer, &gnssFix2)) { - LOG_DEBUG(CAN, "GNSSFix2 decode failed"); - return; - } - dronecanGPSReceiveGNSSFix2(&gnssFix2); } -void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - if (gpsConfig()->provider != GPS_DRONECAN) return; - struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream; +dronecanState_e dronecanGetState(void) +{ + return dronecanState; +} - if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &gnssRTCMStream)) { - LOG_DEBUG(CAN, "RTCMStream decode failed"); - return; - } +uint8_t dronecanGetNodeCount(void) +{ + return activeNodeCount; } -void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { - UNUSED(ins); - struct uavcan_equipment_power_BatteryInfo batteryInfo; +uint32_t dronecanGetBitrateKbps(void) +{ + switch (dronecanConfig()->bitRateKbps){ + case DRONECAN_BITRATE_125KBPS: + return 125; - if (uavcan_equipment_power_BatteryInfo_decode(transfer, &batteryInfo)) { - LOG_DEBUG(CAN, "BatteryInfo decode failed"); - return; - } - dronecanBatterySensorReceiveInfo(&batteryInfo); + case DRONECAN_BITRATE_250KBPS: + return 250; + + case DRONECAN_BITRATE_500KBPS: + return 500; + + case DRONECAN_BITRATE_1000KBPS: + return 1000; + + case DRONECAN_BITRATE_COUNT: + return 0; + } + return 0; } -/* - handle a GetNodeInfo request -*/ +const dronecanNodeInfo_t *dronecanGetNode(uint8_t index) { + if (index < activeNodeCount) return &nodeTable[index]; + return NULL; +} -// TODO: All the data in here is temporary for testing. If actually need to send valid data, edit accordingly. -void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { - uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; - struct uavcan_protocol_GetNodeInfoResponse pkt; +// ---- TX queue --------------------------------------------------------------- - memset(&pkt, 0, sizeof(pkt)); +/* Called from TX-complete ISR only. Already in interrupt context — no NVIC masking needed. + For main-loop use, call processCanardTxQueueSafe() instead. */ +void processCanardTxQueue(void) { + // Transmitting + for (const CanardCANFrame *tx_frame ; (tx_frame = canardPeekTxQueue(&canard)) != NULL;) + { + const int16_t tx_res = canardSTM32Transmit(tx_frame); - node_status.uptime_sec = millis() / 1000ULL; - pkt.status = node_status; + if (tx_res < 0) { + LOG_DEBUG(CAN, "Transmit error %d", tx_res); + canardPopTxQueue(&canard); // Error - discard frame + } else if (tx_res > 0) { + canardPopTxQueue(&canard); // Success - remove from queue + } else { + // tx_res == 0: TX FIFO full, retry later + break; + } + } +} - // fill in your major and minor firmware version - pkt.software_version.major = FC_VERSION_MAJOR; - pkt.software_version.minor = FC_VERSION_MINOR; - pkt.software_version.optional_field_flags = FC_VERSION_PATCH_LEVEL; - pkt.software_version.vcs_commit = strtoul(shortGitRevision, NULL, 16); // need to convert string to integer put git hash in here +// ---- ISR / HAL callbacks ---------------------------------------------------- - // should fill in hardware version - pkt.hardware_version.major = 1; - pkt.hardware_version.minor = 0; +#if defined(STM32H7) +void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes) +{ + UNUSED(hfdcan); + UNUSED(BufferIndexes); + processCanardTxQueue(); +} +#endif +#if defined(STM32F7) +void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } +#endif - // just setting all 16 bytes to 1 for testing - canardSTM32GetUniqueID(pkt.hardware_version.unique_id); +// ---- Internal helpers ------------------------------------------------------- - strncpy((char*)pkt.name.data, FC_FIRMWARE_NAME, sizeof(pkt.name.data)); - pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); +static void processCanardTxQueueSafe(void) { + for (;;) { + // Mask only for the linked-list peek — not for the HAL transmit call + dronecanMaskTxISR(); + const CanardCANFrame *tx_frame = canardPeekTxQueue(&canard); + if (tx_frame == NULL) { + dronecanUnmaskTxISR(); + break; + } + const CanardCANFrame frame_copy = *tx_frame; + dronecanUnmaskTxISR(); - uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + const int16_t tx_res = canardSTM32Transmit(&frame_copy); + if (tx_res == 0) { + break; // HW TX full, ISR will refill when a slot opens + } - dronecanMaskTxISR(); - canardRequestOrRespond(ins, - transfer->source_node_id, - UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, - UAVCAN_PROTOCOL_GETNODEINFO_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - total_size); - dronecanUnmaskTxISR(); + // Re-mask to pop. If the ISR fired during the transmit call and already + // popped this frame, peek will return a different pointer — skip the pop. + dronecanMaskTxISR(); + if (canardPeekTxQueue(&canard) == tx_frame) { + if (tx_res < 0) { + LOG_DEBUG(CAN, "Transmit error %d", tx_res); + } + canardPopTxQueue(&canard); + } + dronecanUnmaskTxISR(); + } } -// Canard Senders +// NOTE: All canard handlers and senders are based on this reference: https://dronecan.github.io/Specification/7._List_of_standard_data_types/ +// Alternatively, you can look at the corresponding generated header file in the dsdlc_generated folder /* send the 1Hz NodeStatus message. This is what allows a node to show @@ -213,7 +310,7 @@ void send_NodeStatus(void) { else { node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL; } - + node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; // Indicates that node is able to communicate over CAN, not that it is in flight. node_status.sub_mode = 0; // Not currently used in dronecan @@ -239,7 +336,24 @@ void send_NodeStatus(void) { } -// Canard Util +/* + This function is called at 1 Hz rate from the main loop. +*/ +static void process1HzTasks(timeUs_t timestamp_usec) +{ + /* + Purge transfers that are no longer transmitted. This can free up some memory + */ + dronecanMaskTxISR(); + canardCleanupStaleTransfers(&canard, timestamp_usec); + dronecanUnmaskTxISR(); + + /* + Transmit the node status message + */ + send_NodeStatus(); +} + /* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received by the local node. @@ -249,7 +363,6 @@ void send_NodeStatus(void) { This function must fill in the out_data_type_signature to be the signature of the message. */ - bool shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, @@ -306,6 +419,147 @@ bool shouldAcceptTransfer(const CanardInstance *ins, return false; } +// Canard Handlers ( Many have code copied from libcanard esc_node example: https://github.com/dronecan/libcanard/blob/master/examples/ESCNode/esc_node.c ) + +void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + struct uavcan_protocol_NodeStatus nodeStatus; + + if (uavcan_protocol_NodeStatus_decode(transfer, &nodeStatus)) { + LOG_DEBUG(CAN, "NodeStatus decode failed"); + return; + } + + uint8_t nodeId = transfer->source_node_id; + for (uint8_t i = 0; i < activeNodeCount; i++) { + if (nodeTable[i].nodeID == nodeId) { + // update health, mode, uptime, vendor_status_code, last_seen_ms + nodeTable[i].health = nodeStatus.health; + nodeTable[i].mode = nodeStatus.mode; + nodeTable[i].uptime_sec = nodeStatus.uptime_sec; + nodeTable[i].vendor_status_code = nodeStatus.vendor_specific_status_code; + nodeTable[i].last_seen_ms = millis(); + return; + } + } + // new node + if (activeNodeCount < DRONECAN_MAX_NODES) { + nodeTable[activeNodeCount].nodeID = nodeId; + nodeTable[activeNodeCount].health = nodeStatus.health; + nodeTable[activeNodeCount].mode = nodeStatus.mode; + nodeTable[activeNodeCount].uptime_sec = nodeStatus.uptime_sec; + nodeTable[activeNodeCount].vendor_status_code = nodeStatus.vendor_specific_status_code; + nodeTable[activeNodeCount].name_len = 0; + nodeTable[activeNodeCount].name[0] = 0; + nodeTable[activeNodeCount].last_seen_ms = millis(); + activeNodeCount++; + } + +} + +void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; + struct uavcan_equipment_gnss_Auxiliary gnssAuxiliary; + + if (uavcan_equipment_gnss_Auxiliary_decode(transfer, &gnssAuxiliary)) { + LOG_DEBUG(CAN, "GNSSAuxiliary decode failed"); + return; + } + dronecanGPSReceiveGNSSAuxiliary(&gnssAuxiliary); +} + +void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; + struct uavcan_equipment_gnss_Fix gnssFix; + + if (uavcan_equipment_gnss_Fix_decode(transfer, &gnssFix)) { + LOG_DEBUG(CAN, "GNSSFix decode failed"); + return; + } + dronecanGPSReceiveGNSSFix(&gnssFix); +} + +void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; + struct uavcan_equipment_gnss_Fix2 gnssFix2; + + if (uavcan_equipment_gnss_Fix2_decode(transfer, &gnssFix2)) { + LOG_DEBUG(CAN, "GNSSFix2 decode failed"); + return; + } + dronecanGPSReceiveGNSSFix2(&gnssFix2); +} + +void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + if (gpsConfig()->provider != GPS_DRONECAN) return; + struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream; + + if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &gnssRTCMStream)) { + LOG_DEBUG(CAN, "RTCMStream decode failed"); + return; + } +} + +void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { + UNUSED(ins); + struct uavcan_equipment_power_BatteryInfo batteryInfo; + + if (uavcan_equipment_power_BatteryInfo_decode(transfer, &batteryInfo)) { + LOG_DEBUG(CAN, "BatteryInfo decode failed"); + return; + } + dronecanBatterySensorReceiveInfo(&batteryInfo); +} + +/* + handle a GetNodeInfo request +*/ + +// TODO: All the data in here is temporary for testing. If actually need to send valid data, edit accordingly. +void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { + uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; + struct uavcan_protocol_GetNodeInfoResponse pkt; + + memset(&pkt, 0, sizeof(pkt)); + + node_status.uptime_sec = millis() / 1000ULL; + pkt.status = node_status; + + // fill in your major and minor firmware version + pkt.software_version.major = FC_VERSION_MAJOR; + pkt.software_version.minor = FC_VERSION_MINOR; + pkt.software_version.optional_field_flags = FC_VERSION_PATCH_LEVEL; + pkt.software_version.vcs_commit = strtoul(shortGitRevision, NULL, 16); // need to convert string to integer put git hash in here + + // should fill in hardware version + pkt.hardware_version.major = 1; + pkt.hardware_version.minor = 0; + + // just setting all 16 bytes to 1 for testing + canardSTM32GetUniqueID(pkt.hardware_version.unique_id); + + strncpy((char*)pkt.name.data, FC_FIRMWARE_NAME, sizeof(pkt.name.data)); + pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); + + uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + + dronecanMaskTxISR(); + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, + UAVCAN_PROTOCOL_GETNODEINFO_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); + dronecanUnmaskTxISR(); +} + /* This callback is invoked by the library when a new message or request or response is received. */ @@ -328,273 +582,31 @@ void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { // check if we want to handle a specific broadcast message switch (transfer->data_type_id) { - case UAVCAN_PROTOCOL_NODESTATUS_ID: + case UAVCAN_PROTOCOL_NODESTATUS_ID: handle_NodeStatus(ins, transfer); break; - - case UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID: + + case UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID: handle_GNSSAuxiliary(ins, transfer); break; - - case UAVCAN_EQUIPMENT_GNSS_FIX_ID: + + case UAVCAN_EQUIPMENT_GNSS_FIX_ID: handle_GNSSFix(ins, transfer); break; - - case UAVCAN_EQUIPMENT_GNSS_FIX2_ID: + + case UAVCAN_EQUIPMENT_GNSS_FIX2_ID: handle_GNSSFix2(ins, transfer); break; - - case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID: + + case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID: handle_GNSSRCTMStream(ins, transfer); break; - + case UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID: handle_BatteryInfo(ins, transfer); break; } } } - -void processCanardTxQueue(void) { - // Transmitting - for (const CanardCANFrame *tx_frame ; (tx_frame = canardPeekTxQueue(&canard)) != NULL;) - { - const int16_t tx_res = canardSTM32Transmit(tx_frame); - - if (tx_res < 0) { - LOG_DEBUG(CAN, "Transmit error %d", tx_res); - canardPopTxQueue(&canard); // Error - discard frame - } else if (tx_res > 0) { - canardPopTxQueue(&canard); // Success - remove from queue - } else { - // tx_res == 0: TX FIFO full, retry later - break; - } - } -} - -static void processCanardTxQueueSafe(void) { - for (;;) { - // Mask only for the linked-list peek — not for the HAL transmit call - dronecanMaskTxISR(); - const CanardCANFrame *tx_frame = canardPeekTxQueue(&canard); - if (tx_frame == NULL) { - dronecanUnmaskTxISR(); - break; - } - const CanardCANFrame frame_copy = *tx_frame; - dronecanUnmaskTxISR(); - - const int16_t tx_res = canardSTM32Transmit(&frame_copy); - if (tx_res == 0) { - break; // HW TX full, ISR will refill when a slot opens - } - - // Re-mask to pop. If the ISR fired during the transmit call and already - // popped this frame, peek will return a different pointer — skip the pop. - dronecanMaskTxISR(); - if (canardPeekTxQueue(&canard) == tx_frame) { - if (tx_res < 0) { - LOG_DEBUG(CAN, "Transmit error %d", tx_res); - } - canardPopTxQueue(&canard); - } - dronecanUnmaskTxISR(); - } -} - -#if defined(STM32H7) -void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes) -{ - UNUSED(hfdcan); - UNUSED(BufferIndexes); - processCanardTxQueue(); -} -#endif -#if defined(STM32F7) -void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } -void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } -void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); processCanardTxQueue(); } -#endif - - -/* - This function is called at 1 Hz rate from the main loop. -*/ -void process1HzTasks(timeUs_t timestamp_usec) -{ - /* - Purge transfers that are no longer transmitted. This can free up some memory - */ - dronecanMaskTxISR(); - canardCleanupStaleTransfers(&canard, timestamp_usec); - dronecanUnmaskTxISR(); - - /* - Transmit the node status message - */ - send_NodeStatus(); -} - -void dronecanInit(void) -{ - uint32_t bitrate = 500000; // At least define 500000 - - switch (dronecanConfig()->bitRateKbps){ - case DRONECAN_BITRATE_125KBPS: - bitrate = 125000; - break; - - case DRONECAN_BITRATE_250KBPS: - bitrate = 250000; - break; - - case DRONECAN_BITRATE_500KBPS: - bitrate = 500000; - break; - - case DRONECAN_BITRATE_1000KBPS: - bitrate = 1000000; - break; - - case DRONECAN_BITRATE_COUNT: - LOG_ERROR(SYSTEM, "Undefined bitrate set in configuration. 500kbps selected"); - bitrate = 500000; - break; - } - if(canardSTM32CAN1_Init(bitrate) != CANARD_OK) - { - LOG_ERROR(CAN, "Unable to initialize the CAN peripheral"); - dronecanState = STATE_DRONECAN_FAILED; - return; - } - /* - Initializing the Libcanard instance. - */ - canardInit(&canard, - memory_pool, - sizeof(memory_pool), - onTransferReceived, - shouldAcceptTransfer, - NULL); - - // Could use DNA (Dynamic Node Allocation) by following example in esc_node.c but that requires a lot of setup and I'm not too sure of what advantage it brings - // Instead, set a different NODE_ID for each device on the CAN bus by configuring node_settings - if (dronecanConfig()->nodeID > 0) { - canardSetLocalNodeID(&canard, dronecanConfig()->nodeID); - } else { - LOG_DEBUG(CAN, "Node ID is 0, this node is anonymous and can't transmit most messages. Please update this in config"); - } -} - -void dronecanUpdate(timeUs_t currentTimeUs) -{ - static timeUs_t next_1hz_service_at = 0; - static timeUs_t busoffTimeUs = 0; - CanardCANFrame rx_frame; - int numMessagesToProcess = 0; - canardProtocolStatus_t protocolStatus = {}; - uint64_t timestamp; - int16_t rx_res; - - switch(dronecanState) { - case STATE_DRONECAN_INIT: - next_1hz_service_at = currentTimeUs + 1000000ULL; // First 1Hz tick in 1 second - dronecanState = STATE_DRONECAN_NORMAL; - break; - - case STATE_DRONECAN_NORMAL: - processCanardTxQueueSafe(); - - for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--) - { - timestamp = millis() * 1000ULL; - rx_res = canardSTM32Receive(&rx_frame); - - if (rx_res < 0) { - LOG_DEBUG(CAN, "Receive error %d", rx_res); - } - else if (rx_res > 0) // Success - process the frame - { - canardHandleRxFrame(&canard, &rx_frame, timestamp); - } - } - // Drain any TX frames queued by RX handlers (e.g. GetNodeInfo responses) - // in the same task cycle so multi-frame transfers complete before timeout. - processCanardTxQueueSafe(); - - if (currentTimeUs >= next_1hz_service_at) - { - next_1hz_service_at += 1000000ULL; - process1HzTasks(currentTimeUs); - processCanardTxQueueSafe(); - - canardSTM32GetProtocolStatus(&protocolStatus); - if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { - LOG_DEBUG(CAN, "CAN status: BusOff=%" PRIu32 " ErrorPassive=%" PRIu32, protocolStatus.BusOff, protocolStatus.ErrorPassive); - } - if (protocolStatus.BusOff != 0) { - dronecanState = STATE_DRONECAN_BUS_OFF; - busoffTimeUs = currentTimeUs; - } - } - break; - - case STATE_DRONECAN_BUS_OFF: - if(currentTimeUs > (busoffTimeUs + 20000)) { // Wait 20ms: worst-case 128x11 recovery is 11.264ms at 125kbps - canardSTM32RecoverFromBusOff(); - busoffTimeUs = currentTimeUs; - canardSTM32GetProtocolStatus(&protocolStatus); - if(protocolStatus.BusOff == 0) { - dronecanState = STATE_DRONECAN_NORMAL; - } - } - break; - - case STATE_DRONECAN_FAILED: - break; - - case STATE_DRONECAN_COUNT: - break; - - } - -} - -dronecanState_e dronecanGetState(void) -{ - return dronecanState; -} - -uint8_t dronecanGetNodeCount(void) -{ - return activeNodeCount; -} - -uint32_t dronecanGetBitrateKbps(void) -{ - switch (dronecanConfig()->bitRateKbps){ - case DRONECAN_BITRATE_125KBPS: - return 125; - - case DRONECAN_BITRATE_250KBPS: - return 250; - - case DRONECAN_BITRATE_500KBPS: - return 500; - - case DRONECAN_BITRATE_1000KBPS: - return 1000; - - case DRONECAN_BITRATE_COUNT: - return 0; - } - return 0; -} - -const dronecanNodeInfo_t *dronecanGetNode(uint8_t index) { - if (index < activeNodeCount) return &nodeTable[index]; - return NULL; -} #endif diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 52c28df7a5d..7751288bfaf 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -41,50 +41,93 @@ static struct RxBuffer_t { static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timings*out_timings); static void canardSTM32GPIO_Init(void); +static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg); +static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg); +static uint8_t rxBufferNumMessages(struct RxBuffer_t *rxBuf); static CAN_HandleTypeDef hcan1; -static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { - uint8_t next; - RxFrame_t *pCurrentRxMsg; +// ---- Public API ------------------------------------------------------------- - next = rxBuf->writeIndex + 1; - if(next >= RX_BUFFER_SIZE){ - next = 0; +/** + * @brief FDCAN1 Initialization Function + * @param hfdcan pointer to an FDCAN_HandleTypeDef structure that contains + * the configuration information for the specified FDCAN. + * @param bitrate desired bitrate to run the CAN network at. + * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + */ +int16_t canardSTM32CAN1_Init(uint32_t bitrate) +{ + struct Timings out_timings; + + __HAL_RCC_CAN1_CLK_ENABLE(); + + CAN_FilterTypeDef sFilterConfig; + sFilterConfig.FilterIdHigh = 0; + sFilterConfig.FilterIdLow = 0; + sFilterConfig.FilterMaskIdHigh = 0; + sFilterConfig.FilterMaskIdLow = 0; + sFilterConfig.FilterFIFOAssignment = CAN_FILTER_FIFO0; + sFilterConfig.FilterBank = 0; + sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK; + sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT; + sFilterConfig.FilterActivation = ENABLE; + + hcan1.Instance = CAN1; + hcan1.Init.Mode = CAN_MODE_NORMAL; + hcan1.Init.TimeTriggeredMode = DISABLE; + hcan1.Init.AutoBusOff = ENABLE; + hcan1.Init.AutoWakeUp = DISABLE; + hcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer + hcan1.Init.ReceiveFifoLocked = DISABLE; + hcan1.Init.TransmitFifoPriority = DISABLE; + + if (!canardSTM32ComputeTimings(bitrate, &out_timings)) + { + LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); + return -CANARD_ERROR_INTERNAL; } - if(next == rxBuf->readIndex) { - return -1; // rxBuf is full + hcan1.Init.Prescaler = out_timings.prescaler; + hcan1.Init.SyncJumpWidth = (uint32_t)out_timings.sjw << CAN_BTR_SJW_Pos; + hcan1.Init.TimeSeg1 = (uint32_t)out_timings.bs1 << CAN_BTR_TS1_Pos; + hcan1.Init.TimeSeg2 = (uint32_t)out_timings.bs2 << CAN_BTR_TS2_Pos; + LOG_DEBUG(CAN, "Prescaler: %d, SJW: %d, BS1: %d, BS2: %d", out_timings.prescaler, out_timings.sjw, out_timings.bs1, out_timings.bs2); + + canardSTM32GPIO_Init(); + if (HAL_CAN_Init(&hcan1) != HAL_OK) + { + LOG_ERROR(CAN, "Failed CAN Init"); + return -CANARD_ERROR_INTERNAL; } - pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->writeIndex]; - memcpy(pCurrentRxMsg, rxMsg, sizeof(RxFrame_t)); - rxBuf->writeIndex = next; - return 0; -} -static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { - uint8_t next; - RxFrame_t *pCurrentRxMsg; + if (HAL_CAN_ConfigFilter(&hcan1, &sFilterConfig) != HAL_OK) { + LOG_ERROR(CAN, "Failed Config Filter"); + return -CANARD_ERROR_INTERNAL; + } - if(rxBuf->writeIndex == rxBuf->readIndex){ - return -1; // Nothing to read + if (HAL_CAN_Start(&hcan1) != HAL_OK) { + LOG_ERROR(CAN, "Failed to Start"); + return -CANARD_ERROR_INTERNAL; } - next = rxBuf->readIndex + 1; - if (next >= RX_BUFFER_SIZE){ - next = 0; + if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) { // persistent Rx notification + LOG_ERROR(CAN, "Failed to activate interrupt"); + return -CANARD_ERROR_INTERNAL; } - pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->readIndex]; - memcpy(rxMsg, pCurrentRxMsg, sizeof(RxFrame_t)); - rxBuf->readIndex = next; - return 0; -} -uint8_t rxBufferNumMessages(struct RxBuffer_t *rxBuf) { - if(rxBuf->writeIndex < rxBuf->readIndex) - return((rxBuf->writeIndex + RX_BUFFER_SIZE) - rxBuf->readIndex); - - return (rxBuf->writeIndex - rxBuf->readIndex); + // Enable interrupt only after all initialization succeeds + // (if any previous step failed, we return early without enabling IRQ) + HAL_NVIC_SetPriority(CAN1_RX0_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); + if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) { + LOG_ERROR(CAN, "Failed to activate TX interrupt"); + return -CANARD_ERROR_INTERNAL; + } + HAL_NVIC_SetPriority(CAN1_TX_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); + + return CANARD_OK; } /** @@ -171,87 +214,64 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { return 0; } -/** - * @brief FDCAN1 Initialization Function - * @param hfdcan pointer to an FDCAN_HandleTypeDef structure that contains - * the configuration information for the specified FDCAN. - * @param bitrate desired bitrate to run the CAN network at. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode - */ -int16_t canardSTM32CAN1_Init(uint32_t bitrate) -{ - struct Timings out_timings; +void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ + uint32_t esr = hcan1.Instance->ESR; + pProtocolStat->BusOff = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_BOF); + pProtocolStat->ErrorPassive = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_EPV); + pProtocolStat->tec = (uint8_t)((esr >> 16) & 0xFF); + pProtocolStat->rec = (uint8_t)((esr >> 24) & 0xFF); + pProtocolStat->lec = (uint8_t)((esr >> 4) & 0x07); +} - __HAL_RCC_CAN1_CLK_ENABLE(); +int32_t canardSTM32GetTxQueueFillLevel(void){ + return 0; +} - CAN_FilterTypeDef sFilterConfig; - sFilterConfig.FilterIdHigh = 0; - sFilterConfig.FilterIdLow = 0; - sFilterConfig.FilterMaskIdHigh = 0; - sFilterConfig.FilterMaskIdLow = 0; - sFilterConfig.FilterFIFOAssignment = CAN_FILTER_FIFO0; - sFilterConfig.FilterBank = 0; - sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK; - sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT; - sFilterConfig.FilterActivation = ENABLE; - - hcan1.Instance = CAN1; - hcan1.Init.Mode = CAN_MODE_NORMAL; - hcan1.Init.TimeTriggeredMode = DISABLE; - hcan1.Init.AutoBusOff = ENABLE; - hcan1.Init.AutoWakeUp = DISABLE; - hcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer - hcan1.Init.ReceiveFifoLocked = DISABLE; - hcan1.Init.TransmitFifoPriority = DISABLE; - - if (!canardSTM32ComputeTimings(bitrate, &out_timings)) - { - LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); - return -CANARD_ERROR_INTERNAL; - } +int32_t canardSTM32GetRxFifoFillLevel(void){ + return rxBufferNumMessages(&RxBuffer); +} - hcan1.Init.Prescaler = out_timings.prescaler; - hcan1.Init.SyncJumpWidth = (uint32_t)out_timings.sjw << CAN_BTR_SJW_Pos; - hcan1.Init.TimeSeg1 = (uint32_t)out_timings.bs1 << CAN_BTR_TS1_Pos; - hcan1.Init.TimeSeg2 = (uint32_t)out_timings.bs2 << CAN_BTR_TS2_Pos; - LOG_DEBUG(CAN, "Prescaler: %d, SJW: %d, BS1: %d, BS2: %d", out_timings.prescaler, out_timings.sjw, out_timings.bs1, out_timings.bs2); +void canardSTM32RecoverFromBusOff(void){ + // No-op: ABOM (CAN_MCR bit 6) is set in canardSTM32CAN1_Init, so hardware + // manages the full bus-off recovery sequence automatically. After 128x11 + // recessive bits, hardware cycles INRQ and clears ESR.BOFF without software + // intervention. See RM0410 ss40.7.6 and CAN_MCR.ABOM, CAN_ESR.BOFF. +} - canardSTM32GPIO_Init(); - if (HAL_CAN_Init(&hcan1) != HAL_OK) - { - LOG_ERROR(CAN, "Failed CAN Init"); - return -CANARD_ERROR_INTERNAL; - } - - if (HAL_CAN_ConfigFilter(&hcan1, &sFilterConfig) != HAL_OK) { - LOG_ERROR(CAN, "Failed Config Filter"); - return -CANARD_ERROR_INTERNAL; - } - - if (HAL_CAN_Start(&hcan1) != HAL_OK) { - LOG_ERROR(CAN, "Failed to Start"); - return -CANARD_ERROR_INTERNAL; - } +/* + get a 16 byte unique ID for this node, this should be based on the CPU unique ID or other unique ID + */ +void canardSTM32GetUniqueID(uint8_t id[16]) { + uint32_t HALUniqueIDs[3]; + // Make Unique ID out of the 96-bit STM32 UID and fill the rest with 0s + memset(id, 0, 16); + HALUniqueIDs[0] = *(uint32_t *)UID_BASE; + HALUniqueIDs[1] = *(uint32_t *)(UID_BASE + 4); + HALUniqueIDs[2] = *(uint32_t *)(UID_BASE + 8); + memcpy(id, HALUniqueIDs, 12); +} - if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_RX_FIFO0_MSG_PENDING) != HAL_OK) { // persistent Rx notification - LOG_ERROR(CAN, "Failed to activate interrupt"); - return -CANARD_ERROR_INTERNAL; - } - - // Enable interrupt only after all initialization succeeds - // (if any previous step failed, we return early without enabling IRQ) - HAL_NVIC_SetPriority(CAN1_RX0_IRQn, NVIC_PRIO_CAN, 0); - HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); - if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) { - LOG_ERROR(CAN, "Failed to activate TX interrupt"); - return -CANARD_ERROR_INTERNAL; - } - HAL_NVIC_SetPriority(CAN1_TX_IRQn, NVIC_PRIO_CAN, 0); - HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); +// ---- ISR / HAL callbacks ---------------------------------------------------- - return CANARD_OK; +void CAN1_RX0_IRQHandler(void) { + HAL_CAN_IRQHandler(&hcan1); +} + +void CAN1_TX_IRQHandler(void) { + HAL_CAN_IRQHandler(&hcan1); +} + +void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { + RxFrame_t frame; + if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &frame.header, frame.data) == HAL_OK) { + if (rxBufferPushFrame(&RxBuffer, &frame) != 0) { + LOG_WARNING(CAN, "RX buffer full, frame dropped"); + } + } } +// ---- Private helpers -------------------------------------------------------- + /** * @brief GPIO Initialization Function * @param None @@ -278,9 +298,10 @@ static void canardSTM32GPIO_Init(void) IOLo(IOGetByTag(IO_TAG(CAN1_STANDBY))); #endif } + static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timings *out_timings) { - + if (target_bitrate < 1) { return false; } @@ -392,56 +413,45 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi return true; } -void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ - uint32_t esr = hcan1.Instance->ESR; - pProtocolStat->BusOff = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_BOF); - pProtocolStat->ErrorPassive = __HAL_CAN_GET_FLAG(&hcan1, CAN_FLAG_EPV); - pProtocolStat->tec = (uint8_t)((esr >> 16) & 0xFF); - pProtocolStat->rec = (uint8_t)((esr >> 24) & 0xFF); - pProtocolStat->lec = (uint8_t)((esr >> 4) & 0x07); -} +static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { + uint8_t next; + RxFrame_t *pCurrentRxMsg; -int32_t canardSTM32GetTxQueueFillLevel(void){ + next = rxBuf->writeIndex + 1; + if(next >= RX_BUFFER_SIZE){ + next = 0; + } + + if(next == rxBuf->readIndex) { + return -1; // rxBuf is full + } + pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->writeIndex]; + memcpy(pCurrentRxMsg, rxMsg, sizeof(RxFrame_t)); + rxBuf->writeIndex = next; return 0; } -int32_t canardSTM32GetRxFifoFillLevel(void){ - return rxBufferNumMessages(&RxBuffer); -} +static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { + uint8_t next; + RxFrame_t *pCurrentRxMsg; -void canardSTM32RecoverFromBusOff(void){ - // No-op: ABOM (CAN_MCR bit 6) is set in canardSTM32CAN1_Init, so hardware - // manages the full bus-off recovery sequence automatically. After 128x11 - // recessive bits, hardware cycles INRQ and clears ESR.BOFF without software - // intervention. See RM0410 ss40.7.6 and CAN_MCR.ABOM, CAN_ESR.BOFF. -} + if(rxBuf->writeIndex == rxBuf->readIndex){ + return -1; // Nothing to read + } -/* - get a 16 byte unique ID for this node, this should be based on the CPU unique ID or other unique ID - */ -void canardSTM32GetUniqueID(uint8_t id[16]) { - uint32_t HALUniqueIDs[3]; - // Make Unique ID out of the 96-bit STM32 UID and fill the rest with 0s - memset(id, 0, 16); - HALUniqueIDs[0] = *(uint32_t *)UID_BASE; - HALUniqueIDs[1] = *(uint32_t *)(UID_BASE + 4); - HALUniqueIDs[2] = *(uint32_t *)(UID_BASE + 8); - memcpy(id, HALUniqueIDs, 12); + next = rxBuf->readIndex + 1; + if (next >= RX_BUFFER_SIZE){ + next = 0; + } + pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->readIndex]; + memcpy(rxMsg, pCurrentRxMsg, sizeof(RxFrame_t)); + rxBuf->readIndex = next; + return 0; } -void CAN1_RX0_IRQHandler(void) { - HAL_CAN_IRQHandler(&hcan1); -} +static uint8_t rxBufferNumMessages(struct RxBuffer_t *rxBuf) { + if(rxBuf->writeIndex < rxBuf->readIndex) + return((rxBuf->writeIndex + RX_BUFFER_SIZE) - rxBuf->readIndex); -void CAN1_TX_IRQHandler(void) { - HAL_CAN_IRQHandler(&hcan1); + return (rxBuf->writeIndex - rxBuf->readIndex); } - -void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { - RxFrame_t frame; - if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &frame.header, frame.data) == HAL_OK) { - if (rxBufferPushFrame(&RxBuffer, &frame) != 0) { - LOG_WARNING(CAN, "RX buffer full, frame dropped"); - } - } -} \ No newline at end of file diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 617fa481e69..fa6ba12fe53 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -31,6 +31,91 @@ static void canardSTM32GPIO_Init(void); static FDCAN_HandleTypeDef hfdcan1; +// ---- Public API ------------------------------------------------------------- + +/** + * @brief CAN1 Initialization Function + * @param bitrate desired bitrate to run the CAN network at. + * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + */ +int16_t canardSTM32CAN1_Init(uint32_t bitrate) +{ + struct Timings out_timings; + + FDCAN_FilterTypeDef sFilterConfig; + sFilterConfig.IdType = FDCAN_EXTENDED_ID; + sFilterConfig.FilterIndex = 0; + sFilterConfig.FilterType = FDCAN_FILTER_DUAL; + sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; + sFilterConfig.FilterID1 = 0x0; + sFilterConfig.FilterID2 = 0x1FFFFFFFU; + hfdcan1.Instance = FDCAN1; + hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD + hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; + hfdcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the 32-slot TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer + hfdcan1.Init.TransmitPause = DISABLE; + hfdcan1.Init.ProtocolException = DISABLE; + + __HAL_RCC_FDCAN_CLK_ENABLE(); + + if (!canardSTM32ComputeTimings(bitrate, &out_timings)) + { + LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); + return -CANARD_ERROR_INTERNAL; + } + + hfdcan1.Init.NominalPrescaler = out_timings.prescaler; + hfdcan1.Init.NominalSyncJumpWidth = out_timings.sjw; + hfdcan1.Init.NominalTimeSeg1 = out_timings.bs1; + hfdcan1.Init.NominalTimeSeg2 = out_timings.bs2; + LOG_DEBUG(CAN, "Prescaler: %d, SJW: %d, BS1: %d, BS2: %d", out_timings.prescaler, out_timings.sjw, out_timings.bs1, out_timings.bs2); + + hfdcan1.Init.RxFifo0ElmtsNbr = 30; + hfdcan1.Init.RxFifo0ElmtSize = FDCAN_DATA_BYTES_8; + hfdcan1.Init.RxBuffersNbr = 1; + hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8; + hfdcan1.Init.StdFiltersNbr = 0; + hfdcan1.Init.ExtFiltersNbr = 1; + hfdcan1.Init.TxFifoQueueElmtsNbr = 3; + hfdcan1.Init.TxEventsNbr = 0; + hfdcan1.Init.TxBuffersNbr = 0; + hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_QUEUE_OPERATION; + hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8; + + canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode + + if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) + { + LOG_ERROR(CAN, "Failed CAN Init"); + return -CANARD_ERROR_INTERNAL; + } + if (HAL_FDCAN_ConfigFilter(&hfdcan1, &sFilterConfig) != HAL_OK) { + LOG_ERROR(CAN, "Failed Config Filter"); + return -CANARD_ERROR_INTERNAL; + } + if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK) { + LOG_ERROR(CAN, "Failed to config FDCAN filter"); + return -CANARD_ERROR_INTERNAL; + } + + if (HAL_FDCAN_Start(&hfdcan1) != HAL_OK) { + LOG_ERROR(CAN, "Failed to Start"); + return -CANARD_ERROR_INTERNAL; + } + + if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_TX_COMPLETE, + FDCAN_TX_BUFFER0 | FDCAN_TX_BUFFER1 | FDCAN_TX_BUFFER2) != HAL_OK) { /* Must match TxFifoQueueElmtsNbr = 3 */ + LOG_ERROR(CAN, "Failed to activate interrupt notification"); + return -CANARD_ERROR_INTERNAL; + } + + /* FDCAN_IT_TX_COMPLETE routes to LINE0 by default (ILS resets to 0) */ + HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn); + + return CANARD_OK; +} + /** * @brief Process CAN message from RxLocation FIFO into rx_frame * @param hfdcan pointer to an FDCAN_HandleTypeDef structure that contains @@ -133,89 +218,51 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { return 0; } -/** - * @brief CAN1 Initialization Function - * @param bitrate desired bitrate to run the CAN network at. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode - */ -int16_t canardSTM32CAN1_Init(uint32_t bitrate) -{ - struct Timings out_timings; - - FDCAN_FilterTypeDef sFilterConfig; - sFilterConfig.IdType = FDCAN_EXTENDED_ID; - sFilterConfig.FilterIndex = 0; - sFilterConfig.FilterType = FDCAN_FILTER_DUAL; - sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; - sFilterConfig.FilterID1 = 0x0; - sFilterConfig.FilterID2 = 0x1FFFFFFFU; - hfdcan1.Instance = FDCAN1; - hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD - hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; - hfdcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the 32-slot TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer - hfdcan1.Init.TransmitPause = DISABLE; - hfdcan1.Init.ProtocolException = DISABLE; - - __HAL_RCC_FDCAN_CLK_ENABLE(); - - if (!canardSTM32ComputeTimings(bitrate, &out_timings)) - { - LOG_ERROR(CAN, "Failed to compute CAN timings for bitrate %lu", (unsigned long)bitrate); - return -CANARD_ERROR_INTERNAL; - } - - hfdcan1.Init.NominalPrescaler = out_timings.prescaler; - hfdcan1.Init.NominalSyncJumpWidth = out_timings.sjw; - hfdcan1.Init.NominalTimeSeg1 = out_timings.bs1; - hfdcan1.Init.NominalTimeSeg2 = out_timings.bs2; - LOG_DEBUG(CAN, "Prescaler: %d, SJW: %d, BS1: %d, BS2: %d", out_timings.prescaler, out_timings.sjw, out_timings.bs1, out_timings.bs2); +void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ + FDCAN_ProtocolStatusTypeDef protocolStatus = {}; + HAL_FDCAN_GetProtocolStatus(&hfdcan1, &protocolStatus); + pProtocolStat->BusOff = protocolStatus.BusOff; + pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; + uint32_t ecr = hfdcan1.Instance->ECR; + pProtocolStat->tec = (uint8_t)(ecr & 0xFF); /* ECR[7:0] */ + pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); /* ECR[14:8] */ + pProtocolStat->lec = (uint8_t)(protocolStatus.LastErrorCode & 0x07); +} - hfdcan1.Init.RxFifo0ElmtsNbr = 30; - hfdcan1.Init.RxFifo0ElmtSize = FDCAN_DATA_BYTES_8; - hfdcan1.Init.RxBuffersNbr = 1; - hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8; - hfdcan1.Init.StdFiltersNbr = 0; - hfdcan1.Init.ExtFiltersNbr = 1; - hfdcan1.Init.TxFifoQueueElmtsNbr = 3; - hfdcan1.Init.TxEventsNbr = 0; - hfdcan1.Init.TxBuffersNbr = 0; - hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_QUEUE_OPERATION; - hfdcan1.Init.TxElmtSize = FDCAN_DATA_BYTES_8; +int32_t canardSTM32GetTxQueueFillLevel(void){ + return 0; +} - canardSTM32GPIO_Init(); // Set up the pins for CAN and optional listen only mode - - if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) - { - LOG_ERROR(CAN, "Failed CAN Init"); - return -CANARD_ERROR_INTERNAL; - } - if (HAL_FDCAN_ConfigFilter(&hfdcan1, &sFilterConfig) != HAL_OK) { - LOG_ERROR(CAN, "Failed Config Filter"); - return -CANARD_ERROR_INTERNAL; - } - if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK) { - LOG_ERROR(CAN, "Failed to config FDCAN filter"); - return -CANARD_ERROR_INTERNAL; - } +int32_t canardSTM32GetRxFifoFillLevel(void){ + return (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan1, FDCAN_RX_FIFO0)); +} - if (HAL_FDCAN_Start(&hfdcan1) != HAL_OK) { - LOG_ERROR(CAN, "Failed to Start"); - return -CANARD_ERROR_INTERNAL; - } +void canardSTM32RecoverFromBusOff(void){ + hfdcan1.Instance->TXBCR = 0xFFFFFFFFU; // Cancel all pending TX requests before recovery + CLEAR_BIT(hfdcan1.Instance->CCCR, FDCAN_CCCR_INIT); +} - if (HAL_FDCAN_ActivateNotification(&hfdcan1, FDCAN_IT_TX_COMPLETE, - FDCAN_TX_BUFFER0 | FDCAN_TX_BUFFER1 | FDCAN_TX_BUFFER2) != HAL_OK) { /* Must match TxFifoQueueElmtsNbr = 3 */ - LOG_ERROR(CAN, "Failed to activate interrupt notification"); - return -CANARD_ERROR_INTERNAL; - } +/* + get a 16 byte unique ID for this node, this should be based on the CPU unique ID or other unique ID + */ +void canardSTM32GetUniqueID(uint8_t id[16]) { + uint32_t HALUniqueIDs[3]; + // Make Unique ID out of the 96-bit STM32 UID and fill the rest with 0s + memset(id, 0, 16); + HALUniqueIDs[0] = HAL_GetUIDw0(); + HALUniqueIDs[1] = HAL_GetUIDw1(); + HALUniqueIDs[2] = HAL_GetUIDw2(); + memcpy(id, HALUniqueIDs, 12); +} - /* FDCAN_IT_TX_COMPLETE routes to LINE0 by default (ILS resets to 0) */ - HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, NVIC_PRIO_CAN, 0); - HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn); +// ---- ISR handler ------------------------------------------------------------ - return CANARD_OK; +void FDCAN1_IT0_IRQHandler(void) { + HAL_FDCAN_IRQHandler(&hfdcan1); } +// ---- Private helpers -------------------------------------------------------- + /** * @brief GPIO Initialization Function * @param None @@ -241,6 +288,7 @@ static void canardSTM32GPIO_Init(void) IOLo(IOGetByTag(IO_TAG(CAN1_STANDBY))); #endif } + static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timings *out_timings) { if (target_bitrate < 1) { @@ -354,44 +402,3 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi return true; } - -void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ - FDCAN_ProtocolStatusTypeDef protocolStatus = {}; - HAL_FDCAN_GetProtocolStatus(&hfdcan1, &protocolStatus); - pProtocolStat->BusOff = protocolStatus.BusOff; - pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; - uint32_t ecr = hfdcan1.Instance->ECR; - pProtocolStat->tec = (uint8_t)(ecr & 0xFF); /* ECR[7:0] */ - pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); /* ECR[14:8] */ - pProtocolStat->lec = (uint8_t)(protocolStatus.LastErrorCode & 0x07); -} - -int32_t canardSTM32GetTxQueueFillLevel(void){ - return 0; -} - -int32_t canardSTM32GetRxFifoFillLevel(void){ - return (HAL_FDCAN_GetRxFifoFillLevel(&hfdcan1, FDCAN_RX_FIFO0)); -} - -void canardSTM32RecoverFromBusOff(void){ - hfdcan1.Instance->TXBCR = 0xFFFFFFFFU; // Cancel all pending TX requests before recovery - CLEAR_BIT(hfdcan1.Instance->CCCR, FDCAN_CCCR_INIT); -} - -/* - get a 16 byte unique ID for this node, this should be based on the CPU unique ID or other unique ID - */ -void canardSTM32GetUniqueID(uint8_t id[16]) { - uint32_t HALUniqueIDs[3]; - // Make Unique ID out of the 96-bit STM32 UID and fill the rest with 0s - memset(id, 0, 16); - HALUniqueIDs[0] = HAL_GetUIDw0(); - HALUniqueIDs[1] = HAL_GetUIDw1(); - HALUniqueIDs[2] = HAL_GetUIDw2(); - memcpy(id, HALUniqueIDs, 12); -} - -void FDCAN1_IT0_IRQHandler(void) { - HAL_FDCAN_IRQHandler(&hfdcan1); -} \ No newline at end of file From 5079420b18530d942fe982585dca0918e5d2180d Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 08:57:44 -0700 Subject: [PATCH 42/48] dronecan: address code review findings - processCanardTxQueueSafe: simplify by holding NVIC mask across transmit call, eliminating the pointer-identity ABA assumption - F7 rxBuffer: add __DMB() barriers between data write and index advance to satisfy C99 memory ordering between ISR and main loop - F7 ComputeTimings: align max_quanta_per_bit with H7 (17, not 18) per Koppe reference recommendation - H7 GetProtocolStatus: document why ECR is read directly vs HAL - H7 RecoverFromBusOff: clarify CCCR.INIT clear is defensive no-op - dronecanUpdate: replace dead STATE_DRONECAN_COUNT case with default - cli: use PRId32 for int32_t format specifiers; add - SITL: remove Doxygen blocks from private static helpers --- src/main/drivers/dronecan/dronecan.c | 20 +++++--------- .../dronecan/libcanard/canard_sitl_driver.c | 26 +------------------ .../libcanard/canard_stm32f7xx_driver.c | 4 ++- .../libcanard/canard_stm32h7xx_driver.c | 4 +++ src/main/fc/cli.c | 5 ++-- 5 files changed, 17 insertions(+), 42 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 5daa3a359f6..7667dff8864 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -180,7 +180,7 @@ void dronecanUpdate(timeUs_t currentTimeUs) case STATE_DRONECAN_FAILED: break; - case STATE_DRONECAN_COUNT: + default: break; } @@ -265,31 +265,23 @@ void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) { UNUSED(hcan); static void processCanardTxQueueSafe(void) { for (;;) { - // Mask only for the linked-list peek — not for the HAL transmit call dronecanMaskTxISR(); const CanardCANFrame *tx_frame = canardPeekTxQueue(&canard); if (tx_frame == NULL) { dronecanUnmaskTxISR(); break; } - const CanardCANFrame frame_copy = *tx_frame; - dronecanUnmaskTxISR(); - - const int16_t tx_res = canardSTM32Transmit(&frame_copy); - if (tx_res == 0) { - break; // HW TX full, ISR will refill when a slot opens - } - - // Re-mask to pop. If the ISR fired during the transmit call and already - // popped this frame, peek will return a different pointer — skip the pop. - dronecanMaskTxISR(); - if (canardPeekTxQueue(&canard) == tx_frame) { + const int16_t tx_res = canardSTM32Transmit(tx_frame); // HAL register write, ~1µs + if (tx_res != 0) { if (tx_res < 0) { LOG_DEBUG(CAN, "Transmit error %d", tx_res); } canardPopTxQueue(&canard); } dronecanUnmaskTxISR(); + if (tx_res == 0) { + break; // HW TX full, ISR will refill when a slot opens + } } } diff --git a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c index 2f70faa459f..21fb893227c 100644 --- a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c @@ -112,11 +112,6 @@ static void sitlCANGetStatsStub(canardProtocolStatus_t *pProtocolStat) { #ifdef __linux__ // SocketCAN implementations -/** - * @brief Initialize SocketCAN interface - * @param bitrate CAN bitrate in bps (for logging, actual rate set via ip link) - * @retval 0 on success, negative on error - */ static int16_t sitlCANInitSocketCAN(uint32_t bitrate) { struct sockaddr_can addr; struct ifreq ifr; @@ -162,9 +157,6 @@ static int16_t sitlCANInitSocketCAN(uint32_t bitrate) { return 0; } -/** - * @brief Convert libcanard frame to Linux CAN frame - */ static void sitlCANFrameToLinux(const CanardCANFrame *const src, struct can_frame *const dst) { memset(dst, 0, sizeof(struct can_frame)); @@ -182,9 +174,6 @@ static void sitlCANFrameToLinux(const CanardCANFrame *const src, struct can_fram } } -/** - * @brief Convert Linux CAN frame to libcanard frame - */ static void sitlCANFrameFromLinux(const struct can_frame *const src, CanardCANFrame *const dst) { memset(dst, 0, sizeof(CanardCANFrame)); @@ -202,11 +191,6 @@ static void sitlCANFrameFromLinux(const struct can_frame *const src, CanardCANFr } } -/** - * @brief Receive a CAN frame via SocketCAN - * @param rx_frame Pointer to frame structure to fill - * @retval 0 if no frame available, 1 if frame received, negative on error - */ static int16_t sitlCANReceiveSocketCAN(CanardCANFrame *const rx_frame) { struct can_frame frame; ssize_t nbytes; @@ -234,11 +218,6 @@ static int16_t sitlCANReceiveSocketCAN(CanardCANFrame *const rx_frame) { return 1; } -/** - * @brief Transmit a CAN frame via SocketCAN - * @param tx_frame Pointer to frame to transmit - * @retval 1 on success, 0 if busy, negative on error - */ static int16_t sitlCANTransmitSocketCAN(const CanardCANFrame* const tx_frame) { struct can_frame frame; ssize_t nbytes; @@ -261,10 +240,7 @@ static int16_t sitlCANTransmitSocketCAN(const CanardCANFrame* const tx_frame) { return 1; // Success } -/** - * @brief Get CAN protocol status from SocketCAN - * @param pProtocolStat Pointer to status structure to fill - */ +/* Always returns zeroes — SocketCAN provides no per-frame error counters via raw sockets. */ static void sitlCANGetStatsSocketCAN(canardProtocolStatus_t *pProtocolStat) { memset(pProtocolStat, 0, sizeof(*pProtocolStat)); } diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 7751288bfaf..637b306e20c 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -325,7 +325,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * 250 kbps 16 17 * 125 kbps 16 17 */ - const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 18; + const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17; static const int MaxSamplePointLocation = 900; /* @@ -427,6 +427,7 @@ static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { } pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->writeIndex]; memcpy(pCurrentRxMsg, rxMsg, sizeof(RxFrame_t)); + __DMB(); // ensure frame data is visible to main loop before writeIndex advance rxBuf->writeIndex = next; return 0; } @@ -443,6 +444,7 @@ static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { if (next >= RX_BUFFER_SIZE){ next = 0; } + __DMB(); // ensure writeIndex read is complete before reading frame data written by ISR pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->readIndex]; memcpy(rxMsg, pCurrentRxMsg, sizeof(RxFrame_t)); rxBuf->readIndex = next; diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index fa6ba12fe53..a777b43f826 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -223,6 +223,7 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ HAL_FDCAN_GetProtocolStatus(&hfdcan1, &protocolStatus); pProtocolStat->BusOff = protocolStatus.BusOff; pProtocolStat->ErrorPassive = protocolStatus.ErrorPassive; + /* HAL provides no accessor for ECR (TEC/REC); read directly. PSR fields (BusOff, ErrorPassive, LEC) come from HAL. */ uint32_t ecr = hfdcan1.Instance->ECR; pProtocolStat->tec = (uint8_t)(ecr & 0xFF); /* ECR[7:0] */ pProtocolStat->rec = (uint8_t)((ecr >> 8) & 0x7F); /* ECR[14:8] */ @@ -239,6 +240,9 @@ int32_t canardSTM32GetRxFifoFillLevel(void){ void canardSTM32RecoverFromBusOff(void){ hfdcan1.Instance->TXBCR = 0xFFFFFFFFU; // Cancel all pending TX requests before recovery + /* H7 FDCAN does not set CCCR.INIT on bus-off entry (unlike F7 bxCAN ABOM). + Hardware runs the 128x11 recessive-bit sequence autonomously. This clear + is a defensive no-op in case software previously entered init mode. */ CLEAR_BIT(hfdcan1.Instance->CCCR, FDCAN_CCCR_INIT); } diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 593ed5dd1cd..124294e4e5f 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -17,6 +17,7 @@ #include #include +#include #include #include #include @@ -4712,8 +4713,8 @@ static void cliDronecan(char *cmdline) cliPrintLinef(" TEC: %u", (unsigned)stat.tec); cliPrintLinef(" REC: %u", (unsigned)stat.rec); cliPrintLinef(" LEC: %s (%u)", lecNames[stat.lec], (unsigned)stat.lec); - cliPrintLinef(" TX queue: %ld", (long)txFill); - cliPrintLinef(" RX buffer: %ld", (long)rxFill); + cliPrintLinef(" TX queue: %" PRId32, txFill); + cliPrintLinef(" RX buffer: %" PRId32, rxFill); } #endif From ae8045646161edf27762ad9324952d38757d0379 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 11:34:59 -0700 Subject: [PATCH 43/48] dronecan: address third code review findings - Make processCanardTxQueue, shouldAcceptTransfer, onTransferReceived static - Replace ISR LOG calls with volatile counters (txErrCount, rxDropCount); log and clear at 1Hz from main loop via canardSTM32GetAndClearRxDropCount() - Add canardSTM32GetAndClearRxDropCount() to driver interface; F7 implements ring-buffer drop counter, H7/SITL return 0 (no SW ring buffer) - Check canardBroadcast/canardRequestOrRespond return values; log on OOM - H7: set RxBuffersNbr=0 (dedicated buffer was unused, wasted message RAM) - H7: reject unmatched standard-ID frames (FDCAN_REJECT for NonMatchingStd) - F7: move NVIC_EnableIRQ calls after all ActivateNotification calls succeed - Fix F7 bxCAN Doxygen: correct @brief, remove wrong @param, fix @retval - Fix all @retval docs: ret==0 is OK (CANARD_OK), not ret==1 - Cast pid_t to uint32_t before bit-shifting in SITL unique ID generation --- src/main/drivers/dronecan/dronecan.c | 34 ++++++++++++++----- .../dronecan/libcanard/canard_sitl_driver.c | 14 +++++--- .../dronecan/libcanard/canard_stm32_driver.h | 1 + .../libcanard/canard_stm32f7xx_driver.c | 28 ++++++++------- .../libcanard/canard_stm32h7xx_driver.c | 14 +++++--- 5 files changed, 61 insertions(+), 30 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 7667dff8864..a75d47dea73 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -41,6 +41,7 @@ PG_RESET_TEMPLATE(dronecanConfig_t, dronecanConfig, static dronecanState_e dronecanState = STATE_DRONECAN_INIT; static uint8_t activeNodeCount = 0; static dronecanNodeInfo_t nodeTable[DRONECAN_MAX_NODES]; +static volatile uint32_t txErrCount = 0; #if defined(STM32H7) static inline void dronecanMaskTxISR(void) { NVIC_DisableIRQ(FDCAN1_IT0_IRQn); } @@ -57,8 +58,8 @@ static inline void dronecanUnmaskTxISR(void) {} static void processCanardTxQueueSafe(void); static void process1HzTasks(timeUs_t timestamp_usec); -bool shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, CanardTransferType transfer_type, uint8_t source_node_id); -void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer); +static bool shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, CanardTransferType transfer_type, uint8_t source_node_id); +static void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer); // ---- Public API ------------------------------------------------------------- @@ -159,6 +160,17 @@ void dronecanUpdate(timeUs_t currentTimeUs) if (protocolStatus.BusOff != 0 || protocolStatus.ErrorPassive != 0) { LOG_DEBUG(CAN, "CAN status: BusOff=%" PRIu32 " ErrorPassive=%" PRIu32, protocolStatus.BusOff, protocolStatus.ErrorPassive); } + + uint32_t rxDrops = canardSTM32GetAndClearRxDropCount(); + uint32_t txErrs = txErrCount; + txErrCount = 0; + if (rxDrops > 0) { + LOG_DEBUG(CAN, "RX drops: %" PRIu32, rxDrops); + } + if (txErrs > 0) { + LOG_DEBUG(CAN, "TX errors: %" PRIu32, txErrs); + } + if (protocolStatus.BusOff != 0) { dronecanState = STATE_DRONECAN_BUS_OFF; busoffTimeUs = currentTimeUs; @@ -227,14 +239,14 @@ const dronecanNodeInfo_t *dronecanGetNode(uint8_t index) { /* Called from TX-complete ISR only. Already in interrupt context — no NVIC masking needed. For main-loop use, call processCanardTxQueueSafe() instead. */ -void processCanardTxQueue(void) { +static void processCanardTxQueue(void) { // Transmitting for (const CanardCANFrame *tx_frame ; (tx_frame = canardPeekTxQueue(&canard)) != NULL;) { const int16_t tx_res = canardSTM32Transmit(tx_frame); if (tx_res < 0) { - LOG_DEBUG(CAN, "Transmit error %d", tx_res); + txErrCount++; // logged from main loop at 1Hz canardPopTxQueue(&canard); // Error - discard frame } else if (tx_res > 0) { canardPopTxQueue(&canard); // Success - remove from queue @@ -317,7 +329,7 @@ void send_NodeStatus(void) { static uint8_t transfer_id; dronecanMaskTxISR(); - canardBroadcast(&canard, + const int16_t bc_res = canardBroadcast(&canard, UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, UAVCAN_PROTOCOL_NODESTATUS_ID, &transfer_id, @@ -325,6 +337,9 @@ void send_NodeStatus(void) { buffer, len); dronecanUnmaskTxISR(); + if (bc_res < 0) { + LOG_DEBUG(CAN, "NodeStatus broadcast failed: %d", bc_res); + } } @@ -355,7 +370,7 @@ static void process1HzTasks(timeUs_t timestamp_usec) This function must fill in the out_data_type_signature to be the signature of the message. */ -bool shouldAcceptTransfer(const CanardInstance *ins, +static bool shouldAcceptTransfer(const CanardInstance *ins, uint64_t *out_data_type_signature, uint16_t data_type_id, CanardTransferType transfer_type, @@ -540,7 +555,7 @@ void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); dronecanMaskTxISR(); - canardRequestOrRespond(ins, + const int16_t rr_res = canardRequestOrRespond(ins, transfer->source_node_id, UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, UAVCAN_PROTOCOL_GETNODEINFO_ID, @@ -550,12 +565,15 @@ void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { &buffer[0], total_size); dronecanUnmaskTxISR(); + if (rr_res < 0) { + LOG_DEBUG(CAN, "GetNodeInfo response failed: %d", rr_res); + } } /* This callback is invoked by the library when a new message or request or response is received. */ -void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { +static void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer) { // switch on data type ID to pass to the right handler function if (transfer->transfer_type == CanardTransferTypeRequest) { // check if we want to handle a specific service request diff --git a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c index 21fb893227c..9308e12660d 100644 --- a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c @@ -328,6 +328,10 @@ int32_t canardSTM32GetRxFifoFillLevel(void) { return 0; } +uint32_t canardSTM32GetAndClearRxDropCount(void) { + return 0; +} + int32_t canardSTM32GetTxQueueFillLevel(void) { return 0; } @@ -359,11 +363,11 @@ void canardSTM32GetUniqueID(uint8_t id[16]) { #ifdef __linux__ // Add process ID for uniqueness between multiple SITL instances - pid_t pid = getpid(); - id[4] = (pid >> 24) & 0xFF; - id[5] = (pid >> 16) & 0xFF; - id[6] = (pid >> 8) & 0xFF; - id[7] = pid & 0xFF; + uint32_t upid = (uint32_t)getpid(); + id[4] = (upid >> 24) & 0xFF; + id[5] = (upid >> 16) & 0xFF; + id[6] = (upid >> 8) & 0xFF; + id[7] = upid & 0xFF; // Add timestamp for additional uniqueness struct timespec ts; diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h b/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h index c5fd6a5133e..9b205f8bbaf 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h +++ b/src/main/drivers/dronecan/libcanard/canard_stm32_driver.h @@ -26,6 +26,7 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame); void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat); int32_t canardSTM32GetTxQueueFillLevel(void); int32_t canardSTM32GetRxFifoFillLevel(void); +uint32_t canardSTM32GetAndClearRxDropCount(void); void canardSTM32RecoverFromBusOff(void); void canardSTM32GetUniqueID(uint8_t id[16]); diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 637b306e20c..d34e3f66be5 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -46,15 +46,14 @@ static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg); static uint8_t rxBufferNumMessages(struct RxBuffer_t *rxBuf); static CAN_HandleTypeDef hcan1; +static volatile uint32_t rxDropCount = 0; // ---- Public API ------------------------------------------------------------- /** - * @brief FDCAN1 Initialization Function - * @param hfdcan pointer to an FDCAN_HandleTypeDef structure that contains - * the configuration information for the specified FDCAN. + * @brief CAN1 (bxCAN) Initialization Function * @param bitrate desired bitrate to run the CAN network at. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32CAN1_Init(uint32_t bitrate) { @@ -115,15 +114,14 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) LOG_ERROR(CAN, "Failed to activate interrupt"); return -CANARD_ERROR_INTERNAL; } - - // Enable interrupt only after all initialization succeeds - // (if any previous step failed, we return early without enabling IRQ) - HAL_NVIC_SetPriority(CAN1_RX0_IRQn, NVIC_PRIO_CAN, 0); - HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); if (HAL_CAN_ActivateNotification(&hcan1, CAN_IT_TX_MAILBOX_EMPTY) != HAL_OK) { LOG_ERROR(CAN, "Failed to activate TX interrupt"); return -CANARD_ERROR_INTERNAL; } + + // Enable IRQs only after all ActivateNotification calls succeed + HAL_NVIC_SetPriority(CAN1_RX0_IRQn, NVIC_PRIO_CAN, 0); + HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); HAL_NVIC_SetPriority(CAN1_TX_IRQn, NVIC_PRIO_CAN, 0); HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); @@ -134,7 +132,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) * @brief Process CAN message from RxLocation FIFO into rx_frame * @param rx_frame pointer to a CanardCANFrame structure where the received CAN message will be * stored. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { RxFrame_t canRxFrame; @@ -170,7 +168,7 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { * @brief Process tx_frame CAN message into Tx FIFO/Queue and transmit it * @param tx_frame pointer to a CanardCANFrame structure that contains the CAN message to * transmit. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { CAN_TxHeaderTypeDef txHeader = {}; @@ -265,11 +263,17 @@ void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { RxFrame_t frame; if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &frame.header, frame.data) == HAL_OK) { if (rxBufferPushFrame(&RxBuffer, &frame) != 0) { - LOG_WARNING(CAN, "RX buffer full, frame dropped"); + rxDropCount++; // logged from main loop via canardSTM32GetAndClearRxDropCount() } } } +uint32_t canardSTM32GetAndClearRxDropCount(void) { + uint32_t count = rxDropCount; + rxDropCount = 0; + return count; +} + // ---- Private helpers -------------------------------------------------------- /** diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index a777b43f826..88e2a3925be 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -36,7 +36,7 @@ static FDCAN_HandleTypeDef hfdcan1; /** * @brief CAN1 Initialization Function * @param bitrate desired bitrate to run the CAN network at. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32CAN1_Init(uint32_t bitrate) { @@ -72,7 +72,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hfdcan1.Init.RxFifo0ElmtsNbr = 30; hfdcan1.Init.RxFifo0ElmtSize = FDCAN_DATA_BYTES_8; - hfdcan1.Init.RxBuffersNbr = 1; + hfdcan1.Init.RxBuffersNbr = 0; hfdcan1.Init.RxBufferSize = FDCAN_DATA_BYTES_8; hfdcan1.Init.StdFiltersNbr = 0; hfdcan1.Init.ExtFiltersNbr = 1; @@ -93,7 +93,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) LOG_ERROR(CAN, "Failed Config Filter"); return -CANARD_ERROR_INTERNAL; } - if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK) { + if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_REJECT, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK) { LOG_ERROR(CAN, "Failed to config FDCAN filter"); return -CANARD_ERROR_INTERNAL; } @@ -124,7 +124,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) * This parameter can be a value of @arg FDCAN_Rx_location. * @param rx_frame pointer to a CanardCANFrame structure where the received CAN message will be * stored. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { if (rx_frame == NULL) { @@ -164,7 +164,7 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { * @brief Process tx_frame CAN message into Tx FIFO/Queue and transmit it * @param tx_frame pointer to a CanardCANFrame structure that contains the CAN message to * transmit. - * @retval ret == 1: OK, ret < 0: CANARD_ERROR, ret == 0: Check hfdcan->ErrorCode + * @retval ret == 0: OK (CANARD_OK), ret < 0: CANARD_ERROR */ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { if (tx_frame == NULL) { @@ -230,6 +230,10 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ pProtocolStat->lec = (uint8_t)(protocolStatus.LastErrorCode & 0x07); } +uint32_t canardSTM32GetAndClearRxDropCount(void) { + return 0; // H7 FIFO0 (30 slots) has no software ring buffer; hardware overflow is tracked via GetProtocolStatus +} + int32_t canardSTM32GetTxQueueFillLevel(void){ return 0; } From aef8196b83e2aba3e1cfbfa1e273c938f59e7962 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 13:13:45 -0700 Subject: [PATCH 44/48] dronecan: address fourth code review findings MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Wrap processCanardTxQueue in #if STM32H7||STM32F7 — function is ISR-only and has no callers in SITL builds; static + no callers caused -Werror=unused-function on CI - Atomic read-clear of txErrCount: hold dronecanMaskTxISR across snapshot+zero to prevent ISR increment being silently dropped - Atomic read-clear of rxDropCount: disable CAN1_RX0_IRQn across snapshot+zero in canardSTM32GetAndClearRxDropCount (F7) - Make all eight file-local handler functions static: send_NodeStatus, handle_NodeStatus, handle_GNSSAuxiliary, handle_GNSSFix, handle_GNSSFix2, handle_GNSSRCTMStream, handle_BatteryInfo, handle_GetNodeInfo - H7 global filter: FDCAN_REJECT_REMOTE for both RTR frame params (was FDCAN_FILTER_REMOTE which passed RTR frames to normal filter) - H7 Receive: add comment that DataLength==byte count holds only in FDCAN_FRAME_CLASSIC mode (FDCAN_DLC_BYTES_0..8 equal 0..8) - F7 ring buffer: use local index snapshots in push/pop to avoid double volatile re-reads of writeIndex/readIndex --- src/main/drivers/dronecan/dronecan.c | 24 +++++++++-------- .../libcanard/canard_stm32f7xx_driver.c | 27 +++++++++---------- .../libcanard/canard_stm32h7xx_driver.c | 3 ++- 3 files changed, 27 insertions(+), 27 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index a75d47dea73..36d4c55057e 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -162,8 +162,10 @@ void dronecanUpdate(timeUs_t currentTimeUs) } uint32_t rxDrops = canardSTM32GetAndClearRxDropCount(); + dronecanMaskTxISR(); uint32_t txErrs = txErrCount; txErrCount = 0; + dronecanUnmaskTxISR(); if (rxDrops > 0) { LOG_DEBUG(CAN, "RX drops: %" PRIu32, rxDrops); } @@ -235,8 +237,9 @@ const dronecanNodeInfo_t *dronecanGetNode(uint8_t index) { return NULL; } -// ---- TX queue --------------------------------------------------------------- +// ---- ISR / HAL callbacks ---------------------------------------------------- +#if defined(STM32H7) || defined(STM32F7) /* Called from TX-complete ISR only. Already in interrupt context — no NVIC masking needed. For main-loop use, call processCanardTxQueueSafe() instead. */ static void processCanardTxQueue(void) { @@ -256,8 +259,7 @@ static void processCanardTxQueue(void) { } } } - -// ---- ISR / HAL callbacks ---------------------------------------------------- +#endif #if defined(STM32H7) void HAL_FDCAN_TxBufferCompleteCallback(FDCAN_HandleTypeDef *hfdcan, uint32_t BufferIndexes) @@ -304,7 +306,7 @@ static void processCanardTxQueueSafe(void) { send the 1Hz NodeStatus message. This is what allows a node to show up in the DroneCAN GUI tool and in the flight controller logs */ -void send_NodeStatus(void) { +static void send_NodeStatus(void) { uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; node_status.uptime_sec = millis() / 1000UL; @@ -428,7 +430,7 @@ static bool shouldAcceptTransfer(const CanardInstance *ins, // Canard Handlers ( Many have code copied from libcanard esc_node example: https://github.com/dronecan/libcanard/blob/master/examples/ESCNode/esc_node.c ) -void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); struct uavcan_protocol_NodeStatus nodeStatus; @@ -464,7 +466,7 @@ void handle_NodeStatus(CanardInstance *ins, CanardRxTransfer *transfer) { } -void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Auxiliary gnssAuxiliary; @@ -476,7 +478,7 @@ void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) { dronecanGPSReceiveGNSSAuxiliary(&gnssAuxiliary); } -void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Fix gnssFix; @@ -488,7 +490,7 @@ void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) { dronecanGPSReceiveGNSSFix(&gnssFix); } -void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_Fix2 gnssFix2; @@ -500,7 +502,7 @@ void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { dronecanGPSReceiveGNSSFix2(&gnssFix2); } -void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); if (gpsConfig()->provider != GPS_DRONECAN) return; struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream; @@ -511,7 +513,7 @@ void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { } } -void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); struct uavcan_equipment_power_BatteryInfo batteryInfo; @@ -527,7 +529,7 @@ void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { */ // TODO: All the data in here is temporary for testing. If actually need to send valid data, edit accordingly. -void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { +static void handle_GetNodeInfo(CanardInstance *ins, CanardRxTransfer *transfer) { uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]; struct uavcan_protocol_GetNodeInfoResponse pkt; diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index d34e3f66be5..d8cd507fb87 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -269,8 +269,10 @@ void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) { } uint32_t canardSTM32GetAndClearRxDropCount(void) { + HAL_NVIC_DisableIRQ(CAN1_RX0_IRQn); uint32_t count = rxDropCount; rxDropCount = 0; + HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); return count; } @@ -418,39 +420,34 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi } static int8_t rxBufferPushFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { - uint8_t next; - RxFrame_t *pCurrentRxMsg; - - next = rxBuf->writeIndex + 1; - if(next >= RX_BUFFER_SIZE){ + uint8_t wi = rxBuf->writeIndex; // snapshot: only this ISR writes writeIndex + uint8_t next = wi + 1; + if (next >= RX_BUFFER_SIZE) { next = 0; } - if(next == rxBuf->readIndex) { + if (next == rxBuf->readIndex) { return -1; // rxBuf is full } - pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->writeIndex]; - memcpy(pCurrentRxMsg, rxMsg, sizeof(RxFrame_t)); + memcpy(&rxBuf->rxMsg[wi], rxMsg, sizeof(RxFrame_t)); __DMB(); // ensure frame data is visible to main loop before writeIndex advance rxBuf->writeIndex = next; return 0; } static int8_t rxBufferPopFrame(struct RxBuffer_t *rxBuf, RxFrame_t *rxMsg) { - uint8_t next; - RxFrame_t *pCurrentRxMsg; + uint8_t ri = rxBuf->readIndex; // snapshot: only main loop writes readIndex - if(rxBuf->writeIndex == rxBuf->readIndex){ + if (rxBuf->writeIndex == ri) { return -1; // Nothing to read } - next = rxBuf->readIndex + 1; - if (next >= RX_BUFFER_SIZE){ + uint8_t next = ri + 1; + if (next >= RX_BUFFER_SIZE) { next = 0; } __DMB(); // ensure writeIndex read is complete before reading frame data written by ISR - pCurrentRxMsg = &rxBuf->rxMsg[rxBuf->readIndex]; - memcpy(rxMsg, pCurrentRxMsg, sizeof(RxFrame_t)); + memcpy(rxMsg, &rxBuf->rxMsg[ri], sizeof(RxFrame_t)); rxBuf->readIndex = next; return 0; } diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 88e2a3925be..c0e0b0f7c72 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -93,7 +93,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) LOG_ERROR(CAN, "Failed Config Filter"); return -CANARD_ERROR_INTERNAL; } - if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_REJECT, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE) != HAL_OK) { + if (HAL_FDCAN_ConfigGlobalFilter(&hfdcan1, FDCAN_REJECT, FDCAN_ACCEPT_IN_RX_FIFO0, FDCAN_REJECT_REMOTE, FDCAN_REJECT_REMOTE) != HAL_OK) { LOG_ERROR(CAN, "Failed to config FDCAN filter"); return -CANARD_ERROR_INTERNAL; } @@ -147,6 +147,7 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { rx_frame->id |= CANARD_CAN_FRAME_RTR; } + /* FDCAN_DLC_BYTES_0..8 equal 0..8, so DataLength is the byte count in FDCAN_FRAME_CLASSIC mode. */ rx_frame->data_len = RxHeader.DataLength; memcpy(rx_frame->data, RxData, RxHeader.DataLength); From 8e3940bf30a91fab51318797181c85b11453c46f Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 13:41:22 -0700 Subject: [PATCH 45/48] dronecan: address fifth code review findings - H7 Transmit: add FDCAN_FRAME_CLASSIC comment on DataLength assignment matching the comment already on the receive path - F7 init: add comment explaining pre-shifted timing register values - SITL: map RTR flag in sitlCANFrameToLinux/FromLinux, consistent with hardware drivers - SITL canardSTM32Transmit: add ERR frame guard matching hardware drivers - handle_GNSSRCTMStream: remove dead decode, add comment that RTCM forwarding is not yet implemented - dronecanInit: add default case to bitrate switch for EEPROM corruption - vendor_specific_status_code: explicit (uint16_t) cast with comment acknowledging bits 16-30 of armingFlags are not transmitted - fport.c: remove dead static volatile frameErrors counter (written but never read; triggered -Werror=unused-but-set-variable on GCC 16) --- src/main/drivers/dronecan/dronecan.c | 16 ++++++++-------- .../dronecan/libcanard/canard_sitl_driver.c | 10 +++++++++- .../dronecan/libcanard/canard_stm32f7xx_driver.c | 1 + .../dronecan/libcanard/canard_stm32h7xx_driver.c | 2 +- src/main/rx/fport.c | 2 -- 5 files changed, 19 insertions(+), 12 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 36d4c55057e..b062e919acd 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -88,6 +88,11 @@ void dronecanInit(void) LOG_ERROR(SYSTEM, "Undefined bitrate set in configuration. 500kbps selected"); bitrate = 500000; break; + + default: + LOG_ERROR(SYSTEM, "Invalid bitrate setting, defaulting to 500kbps"); + bitrate = 500000; + break; } if(canardSTM32CAN1_Init(bitrate) != CANARD_OK) { @@ -321,7 +326,7 @@ static void send_NodeStatus(void) { node_status.sub_mode = 0; // Not currently used in dronecan // put whatever you like in here for display in GUI - node_status.vendor_specific_status_code = armingFlags; + node_status.vendor_specific_status_code = (uint16_t)(armingFlags & 0xFFFF); /* field is 16-bit by UAVCAN spec; bits 16-30 of armingFlags are not transmitted */ uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer); @@ -504,13 +509,8 @@ static void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) { static void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) { UNUSED(ins); - if (gpsConfig()->provider != GPS_DRONECAN) return; - struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream; - - if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &gnssRTCMStream)) { - LOG_DEBUG(CAN, "RTCMStream decode failed"); - return; - } + UNUSED(transfer); + /* RTCM forwarding not yet implemented. Accepted in shouldAcceptTransfer for future use. */ } static void handle_BatteryInfo(CanardInstance *ins, CanardRxTransfer *transfer) { diff --git a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c index 9308e12660d..9b02702e2fe 100644 --- a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c @@ -167,6 +167,10 @@ static void sitlCANFrameToLinux(const CanardCANFrame *const src, struct can_fram dst->can_id = src->id & CANARD_CAN_STD_ID_MASK; } + if (src->id & CANARD_CAN_FRAME_RTR) { + dst->can_id |= CAN_RTR_FLAG; + } + // Copy data dst->can_dlc = src->data_len; if (src->data_len > 0) { @@ -184,6 +188,10 @@ static void sitlCANFrameFromLinux(const struct can_frame *const src, CanardCANFr dst->id = src->can_id & CANARD_CAN_STD_ID_MASK; } + if (src->can_id & CAN_RTR_FLAG) { + dst->id |= CANARD_CAN_FRAME_RTR; + } + // Copy data dst->data_len = src->can_dlc; if (src->can_dlc > 0) { @@ -275,7 +283,7 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { * @retval 1 on success, 0 if busy, negative on error */ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { - if (tx_frame == NULL) { + if (tx_frame == NULL || (tx_frame->id & CANARD_CAN_FRAME_ERR)) { return -CANARD_ERROR_INVALID_ARGUMENT; } diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index d8cd507fb87..8b367e7a4c4 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -88,6 +88,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) } hcan1.Init.Prescaler = out_timings.prescaler; + /* F7 bxCAN HAL ORs these directly into BTR; values must be pre-shifted to their register positions */ hcan1.Init.SyncJumpWidth = (uint32_t)out_timings.sjw << CAN_BTR_SJW_Pos; hcan1.Init.TimeSeg1 = (uint32_t)out_timings.bs1 << CAN_BTR_TS1_Pos; hcan1.Init.TimeSeg2 = (uint32_t)out_timings.bs2 << CAN_BTR_TS2_Pos; diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index c0e0b0f7c72..9fccf8ea4b1 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -188,7 +188,7 @@ int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) { TxHeader.Identifier = tx_frame->id & CANARD_CAN_STD_ID_MASK; } - TxHeader.DataLength = tx_frame->data_len; + TxHeader.DataLength = tx_frame->data_len; /* FDCAN_DLC_BYTES_0..8 == 0..8; valid only in FDCAN_FRAME_CLASSIC mode */ if (tx_frame->id & CANARD_CAN_FRAME_RTR) { TxHeader.TxFrameType = FDCAN_REMOTE_FRAME; diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 0ef3e8b2b63..32f8c638fe2 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -149,8 +149,6 @@ static serialPort_t *fportPort; static void reportFrameError(uint8_t errorReason) { UNUSED(errorReason); - static volatile uint16_t frameErrors = 0; - frameErrors++; } // Receive ISR callback From 2c2f8418c0c596965ab469a371f2d602c1c81681 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 14:28:44 -0700 Subject: [PATCH 46/48] dronecan: address sixth code review findings - H7 Receive: add bounds guard on DataLength before assignment to data_len (uint8_t); mirrors existing TX path guard; safe no-op in FDCAN_FRAME_CLASSIC mode but prevents silent truncation if DLC ever exceeds 8 - F7: fix stale comment hfdcan->ErrorCode -> hcan1.ErrorCode - dronecanInit: fix mixed tab/space indentation in canardInit() call - dronecanGetBitrateKbps: return 500 for DRONECAN_BITRATE_COUNT and default cases, matching what dronecanInit actually selects - Fix typo: incremeneted -> incremented - SITL GetRxFifoFillLevel: add comment explaining FIONREAD on SOCK_RAW returns next-datagram size only, so result is 0 or 1 --- src/main/drivers/dronecan/dronecan.c | 16 ++++++++-------- .../dronecan/libcanard/canard_sitl_driver.c | 4 +++- .../dronecan/libcanard/canard_stm32f7xx_driver.c | 2 +- .../dronecan/libcanard/canard_stm32h7xx_driver.c | 7 +++++-- 4 files changed, 17 insertions(+), 12 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index b062e919acd..2c657af5daf 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -104,11 +104,11 @@ void dronecanInit(void) Initializing the Libcanard instance. */ canardInit(&canard, - memory_pool, - sizeof(memory_pool), - onTransferReceived, - shouldAcceptTransfer, - NULL); + memory_pool, + sizeof(memory_pool), + onTransferReceived, + shouldAcceptTransfer, + NULL); // Could use DNA (Dynamic Node Allocation) by following example in esc_node.c but that requires a lot of setup and I'm not too sure of what advantage it brings // Instead, set a different NODE_ID for each device on the CAN bus by configuring node_settings @@ -232,9 +232,9 @@ uint32_t dronecanGetBitrateKbps(void) return 1000; case DRONECAN_BITRATE_COUNT: - return 0; + default: + return 500; } - return 0; } const dronecanNodeInfo_t *dronecanGetNode(uint8_t index) { @@ -331,7 +331,7 @@ static void send_NodeStatus(void) { uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer); // we need a static variable for the transfer ID. This is - // incremeneted on each transfer, allowing for detection of packet + // incremented on each transfer, allowing for detection of packet // loss static uint8_t transfer_id; diff --git a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c index 9b02702e2fe..45c7639b5e4 100644 --- a/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_sitl_driver.c @@ -327,8 +327,10 @@ int32_t canardSTM32GetRxFifoFillLevel(void) { #ifdef __linux__ if (can_mode == SITL_CAN_MODE_SOCKETCAN && can_socket >= 0) { int available; + /* FIONREAD on SOCK_RAW returns the byte size of the next pending datagram only, + so this yields 0 or 1 — SITL processes at most one frame per scheduler tick. */ if (ioctl(can_socket, FIONREAD, &available) == 0) { - return available / sizeof(struct can_frame); + return available / (int)sizeof(struct can_frame); } } #endif diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 8b367e7a4c4..9c8f8b472b1 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -161,7 +161,7 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { rx_frame->iface_id = 0; return 1; } - // Either no CAN msg to be read, or an error that can be read from hfdcan->ErrorCode + // Either no CAN msg to be read, or an error that can be read from hcan1.ErrorCode return 0; } diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index 9fccf8ea4b1..acf902e7056 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -148,8 +148,11 @@ int16_t canardSTM32Receive(CanardCANFrame *const rx_frame) { } /* FDCAN_DLC_BYTES_0..8 equal 0..8, so DataLength is the byte count in FDCAN_FRAME_CLASSIC mode. */ - rx_frame->data_len = RxHeader.DataLength; - memcpy(rx_frame->data, RxData, RxHeader.DataLength); + if (RxHeader.DataLength > CANARD_CAN_FRAME_MAX_DATA_LEN) { + return -CANARD_ERROR_INVALID_ARGUMENT; /* should never happen in FDCAN_FRAME_CLASSIC mode */ + } + rx_frame->data_len = (uint8_t)RxHeader.DataLength; + memcpy(rx_frame->data, RxData, rx_frame->data_len); // assume a single interface rx_frame->iface_id = 0; From f462dc66c1986652eca501b64aeb29e8bd9db101 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 14:58:25 -0700 Subject: [PATCH 47/48] dronecan: fix H7 FDCAN filter type to accept all extended IDs FDCAN_FILTER_DUAL with FilterID1=0x0, FilterID2=0x1FFFFFFF only matched those two exact IDs. Replace with FDCAN_FILTER_MASK (pattern=0, mask=0) which accepts any extended ID. Also fix stale comments in H7 driver and dronecanInit. --- src/main/drivers/dronecan/dronecan.c | 2 +- .../drivers/dronecan/libcanard/canard_stm32h7xx_driver.c | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/dronecan/dronecan.c b/src/main/drivers/dronecan/dronecan.c index 2c657af5daf..12f5dbfb117 100644 --- a/src/main/drivers/dronecan/dronecan.c +++ b/src/main/drivers/dronecan/dronecan.c @@ -65,7 +65,7 @@ static void onTransferReceived(CanardInstance *ins, CanardRxTransfer *transfer); void dronecanInit(void) { - uint32_t bitrate = 500000; // At least define 500000 + uint32_t bitrate = 500000; switch (dronecanConfig()->bitRateKbps){ case DRONECAN_BITRATE_125KBPS: diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c index acf902e7056..15e7e885896 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c @@ -45,10 +45,10 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) FDCAN_FilterTypeDef sFilterConfig; sFilterConfig.IdType = FDCAN_EXTENDED_ID; sFilterConfig.FilterIndex = 0; - sFilterConfig.FilterType = FDCAN_FILTER_DUAL; + sFilterConfig.FilterType = FDCAN_FILTER_MASK; /* ID1=pattern 0x0, ID2=mask 0x0: all bits don't care, accept any extended ID */ sFilterConfig.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; sFilterConfig.FilterID1 = 0x0; - sFilterConfig.FilterID2 = 0x1FFFFFFFU; + sFilterConfig.FilterID2 = 0x0; hfdcan1.Instance = FDCAN1; hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; // Initialize in CAN2.0 mode not CAN_FD hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; @@ -235,7 +235,7 @@ void canardSTM32GetProtocolStatus(canardProtocolStatus_t *pProtocolStat){ } uint32_t canardSTM32GetAndClearRxDropCount(void) { - return 0; // H7 FIFO0 (30 slots) has no software ring buffer; hardware overflow is tracked via GetProtocolStatus + return 0; // H7 FIFO0 (30 slots) has no software ring buffer; FIFO overflow drops are not currently counted } int32_t canardSTM32GetTxQueueFillLevel(void){ From 48fcbd036535ba9c49c96b91fe593d70ae16b733 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 12 Jun 2026 20:42:47 -0700 Subject: [PATCH 48/48] Enforce FIFO ordering to prevent spin errors in multi frame messages on bxCan (F7) targets. Set max quanta per bit to 18 unconditionally to fix 1MBps on bxCan. --- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c index 9c8f8b472b1..16b15a99d0a 100644 --- a/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c +++ b/src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c @@ -79,7 +79,7 @@ int16_t canardSTM32CAN1_Init(uint32_t bitrate) hcan1.Init.AutoWakeUp = DISABLE; hcan1.Init.AutoRetransmission = DISABLE; // ENABLE fills the TX FIFO on a degraded bus; DroneCAN reliability is handled at the application layer hcan1.Init.ReceiveFifoLocked = DISABLE; - hcan1.Init.TransmitFifoPriority = DISABLE; + hcan1.Init.TransmitFifoPriority = ENABLE; if (!canardSTM32ComputeTimings(bitrate, &out_timings)) { @@ -332,7 +332,7 @@ static bool canardSTM32ComputeTimings(const uint32_t target_bitrate, struct Timi * 250 kbps 16 17 * 125 kbps 16 17 */ - const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17; + const int max_quanta_per_bit = 18; //(target_bitrate >= 1000000) ? 10 : 17; static const int MaxSamplePointLocation = 900; /*