From 52aa6670f4ffde1fadb5a1af9fbb00d7fdef834a Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 23 May 2026 07:07:41 -0700 Subject: [PATCH 01/41] 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 8c403b7482964ce8fda11c29da3158a806a78abb Mon Sep 17 00:00:00 2001 From: daijoubu Date: Wed, 27 May 2026 19:43:26 -0700 Subject: [PATCH 02/41] dronecan/h7: fix FDCAN kernel clock ordering, SJW, auto-retransmission, and PLL2 clock source - Move FDCAN kernel clock config (RCC_FDCANCLKSOURCE_PLL) before canardSTM32ComputeTimings() so HAL_RCCEx_GetPeriphCLKFreq returns the correct frequency for timing calculation. - Reduce SJW from 8 to 1 for tighter synchronization. - Set TxBuffersNbr=0 (unused with TX FIFO, TxFifoQueueElmtsNbr=32). - Enable FDCAN auto-retransmission to match F7 behavior and avoid escalating transient TX errors into bus-off. - Reduce bus-off recovery delay from 100ms to 1ms (auto-retransmission makes bus-off rare; near-instant recovery is safe). - Make PLL2M dynamic from HSE_VALUE and set PLL2Q=10 for 80 MHz FDCAN kernel clock. Add USE_DRONECAN guard to configure FDCAN clock from PLL2, keeping VCO=800MHz for all HSE frequencies. --- src/main/drivers/dronecan/dronecan.c | 2 +- .../libcanard/canard_stm32h7xx_driver.c | 30 ++++++++----------- src/main/target/system_stm32h7xx.c | 25 +++++++++++----- 3 files changed, 32 insertions(+), 25 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 6ec0d1c4002..7e1628c2fd6 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -497,17 +497,28 @@ void SystemClock_Config(void) RCC_PeriphClkInit.I2c4ClockSelection = RCC_I2C4CLKSOURCE_D3PCLK1; HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); -#ifdef USE_SDCARD_SDIO - RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC; - RCC_PeriphClkInit.PLL2.PLL2M = 5; - RCC_PeriphClkInit.PLL2.PLL2N = 500; - RCC_PeriphClkInit.PLL2.PLL2P = 2; // 500Mhz - 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 +#if defined(USE_SDCARD_SDIO) || defined(USE_DRONECAN) + // PLL2 provides SDMMC (200MHz via PLL2R) and FDCAN (80MHz via PLL2Q) + // PLL2M scales with HSE to keep VCO=800MHz for all HSE frequencies + RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1000000 / 2; + RCC_PeriphClkInit.PLL2.PLL2N = 400; + RCC_PeriphClkInit.PLL2.PLL2P = 2; + RCC_PeriphClkInit.PLL2.PLL2Q = 10; // 80 Mhz - FDCAN + 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.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; HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); #endif From 30019bda2f39778b4a3ce3b092026b1d2bd55ee1 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 19:47:01 -0700 Subject: [PATCH 03/41] 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 ad975a76fbfcb22130bb1fba5d628e1a1e04e9e7 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 20:00:26 -0700 Subject: [PATCH 04/41] 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 14e0eeb0d42fc2f1f0ec8692e700dba740470281 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 20:44:20 -0700 Subject: [PATCH 05/41] 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 c6276b9aed40d975fc2d9fa65d2df270a6187724 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Thu, 28 May 2026 22:37:26 -0700 Subject: [PATCH 06/41] 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 -- src/main/target/system_stm32h7xx.c | 6 +++--- 3 files changed, 3 insertions(+), 17 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; diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index 7e1628c2fd6..9f86300ed13 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -499,9 +499,9 @@ void SystemClock_Config(void) #if defined(USE_SDCARD_SDIO) || defined(USE_DRONECAN) // PLL2 provides SDMMC (200MHz via PLL2R) and FDCAN (80MHz via PLL2Q) - // PLL2M scales with HSE to keep VCO=800MHz for all HSE frequencies - RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1000000 / 2; - RCC_PeriphClkInit.PLL2.PLL2N = 400; + // VCO input = 1.6 MHz (HSE / M), VCO output = 800 MHz (1.6 * N=500) + RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; + RCC_PeriphClkInit.PLL2.PLL2N = 500; RCC_PeriphClkInit.PLL2.PLL2P = 2; RCC_PeriphClkInit.PLL2.PLL2Q = 10; // 80 Mhz - FDCAN RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200Mhz HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV From 98501a4a888dad27c3ca62c90571f7140767b7a5 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 07:57:53 -0700 Subject: [PATCH 07/41] 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 892b0462df3dfbab07f5c3d5a8b8e5ef3dad393f Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 08:28:45 -0700 Subject: [PATCH 08/41] 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 37267ebeb889301ee32aba0d2006f7826a7c3a86 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 08:36:56 -0700 Subject: [PATCH 09/41] 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 9575628e22cebf39f9f0f243f9146a34c59d6335 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:00:52 -0700 Subject: [PATCH 10/41] 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 f05d37f35efb0a69b37c36d4b82ad48012dada43 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:18:31 -0700 Subject: [PATCH 11/41] 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 76486e7d22b4f5094b4f55f842ee6a9b867d673b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 09:58:23 -0700 Subject: [PATCH 12/41] 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 bf926a6aad87fb9452a9229fca8e9bc5f42c555b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 10:01:49 -0700 Subject: [PATCH 13/41] 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 1976edaa8e0..03ded35d7c2 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4198,7 +4198,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 a2ff926c35f905644f44cf4ca3c2549da7398a5e Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 10:11:43 -0700 Subject: [PATCH 14/41] dronecan/h7: check PLL2 config return value; call Error_Handler on failure Consistent with existing PLL1 error handling in the same file. --- src/main/target/system_stm32h7xx.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index 9f86300ed13..f0209d39970 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -519,7 +519,9 @@ void SystemClock_Config(void) RCC_PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PLL2; #endif RCC_PeriphClkInit.PeriphClockSelection = periphSel; - HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); + if (HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit) != HAL_OK) { + Error_Handler(); + } #endif #ifdef USE_QUADSPI From 13d33f87d3b237509dfa6222330d8b66a3c19d62 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 10:16:07 -0700 Subject: [PATCH 15/41] 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 d50900c520776664f124d0f53d5ca29ff9406b28 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 11:45:36 -0700 Subject: [PATCH 16/41] 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 3a016fbcb2397243734ab5dc8e6b1c99c9f68531 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 11:56:35 -0700 Subject: [PATCH 17/41] 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 8559b3ab213f7b38e9b98708baef6ef339462b0b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 12:05:41 -0700 Subject: [PATCH 18/41] 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 7a2ea8a937e844461e4f8090aacd9ae65bdebe88 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 13:15:55 -0700 Subject: [PATCH 19/41] 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 9cd08120aa5e28a0330301c7309b553cb0ea2b20 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 13:19:08 -0700 Subject: [PATCH 20/41] dronecan/h7: add static_assert for HSE_VALUE divisibility in PLL2M calculation HSE_VALUE / 1600000 silently truncates if HSE is not an exact multiple of 1.6MHz. All current H7 targets use 8MHz or 25MHz HSE (both exact multiples), but a future board with a non-standard crystal would compute a wrong PLL2M and get the wrong FDCAN/SDMMC clocks. The assert catches this at compile time. --- 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 f0209d39970..aeb54164e7c 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) // PLL2 provides SDMMC (200MHz via PLL2R) and FDCAN (80MHz via PLL2Q) // VCO input = 1.6 MHz (HSE / M), VCO output = 800 MHz (1.6 * N=500) + // HSE_VALUE must be an exact multiple of 1600000 for integer division to give the correct M divider. + // All supported H7 targets use 8MHz or 25MHz HSE (÷5 or ÷16), both exact multiples. + static_assert(HSE_VALUE % 1600000 == 0, "HSE_VALUE must be a multiple of 1.6MHz for PLL2M calculation"); RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; RCC_PeriphClkInit.PLL2.PLL2N = 500; RCC_PeriphClkInit.PLL2.PLL2P = 2; From 129c1c99c48c870ae44d52d9d9f6c74711240e19 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 13:49:16 -0700 Subject: [PATCH 21/41] 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 442e15cc9dd60935624f56cc02c22985a2f60a39 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:08:50 -0700 Subject: [PATCH 22/41] 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 d9a87e2208f523aa72f339722372adc2d23a3cf7 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:15:13 -0700 Subject: [PATCH 23/41] 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 | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index aeb54164e7c..e7bc40b6a54 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -501,7 +501,9 @@ void SystemClock_Config(void) // PLL2 provides SDMMC (200MHz via PLL2R) and FDCAN (80MHz via PLL2Q) // VCO input = 1.6 MHz (HSE / M), VCO output = 800 MHz (1.6 * N=500) // HSE_VALUE must be an exact multiple of 1600000 for integer division to give the correct M divider. - // All supported H7 targets use 8MHz or 25MHz HSE (÷5 or ÷16), both exact multiples. + // CMake sets HSE_VALUE per-target via -DHSE_VALUE= (default 8MHz); the stm32h7xx_hal_conf.h + // fallback of 25MHz is never used for real hardware. Current targets: 8MHz (÷5) and 16MHz (÷10). + // If adding a new target with a non-multiple HSE, this assert will fire — choose a different VCO input. static_assert(HSE_VALUE % 1600000 == 0, "HSE_VALUE must be a multiple of 1.6MHz for PLL2M calculation"); RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; RCC_PeriphClkInit.PLL2.PLL2N = 500; From fe869b5eb7432875ec97ff77d16a5ec036419e96 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:28:53 -0700 Subject: [PATCH 24/41] 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 7e5e00c0c9413dda47cb5376977a567d2d360439 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:31:02 -0700 Subject: [PATCH 25/41] =?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 a7d6e9be77c9f22c7ee619a3e4220fd56a5fd421 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:38:27 -0700 Subject: [PATCH 26/41] 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 ef1995298c85a046646b148c26ee05ab57d0ab17 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:44:35 -0700 Subject: [PATCH 27/41] 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 f0b24e5669b3bbe5e4acb553f0e03ff7cac6706a Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:50:17 -0700 Subject: [PATCH 28/41] 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 327c51aced0d5022de247a85524c6db42ef018fd Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:54:19 -0700 Subject: [PATCH 29/41] =?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 e2caa083820ec11b8b141f5b44ff604633d9c16b Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:55:14 -0700 Subject: [PATCH 30/41] dronecan/h7: use STATIC_ASSERT macro instead of C11 static_assert Project builds with -std=gnu99 and uses STATIC_ASSERT from common/utils.h throughout. The C11 static_assert keyword is a GCC extension under gnu99 and inconsistent with the project convention. --- src/main/target/system_stm32h7xx.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c index e7bc40b6a54..b6683072677 100644 --- a/src/main/target/system_stm32h7xx.c +++ b/src/main/target/system_stm32h7xx.c @@ -504,7 +504,7 @@ void SystemClock_Config(void) // CMake sets HSE_VALUE per-target via -DHSE_VALUE= (default 8MHz); the stm32h7xx_hal_conf.h // fallback of 25MHz is never used for real hardware. Current targets: 8MHz (÷5) and 16MHz (÷10). // If adding a new target with a non-multiple HSE, this assert will fire — choose a different VCO input. - static_assert(HSE_VALUE % 1600000 == 0, "HSE_VALUE must be a multiple of 1.6MHz for PLL2M calculation"); + STATIC_ASSERT(HSE_VALUE % 1600000 == 0, HSE_VALUE_must_be_a_multiple_of_1_6MHz_for_PLL2M_calculation); RCC_PeriphClkInit.PLL2.PLL2M = HSE_VALUE / 1600000; RCC_PeriphClkInit.PLL2.PLL2N = 500; RCC_PeriphClkInit.PLL2.PLL2P = 2; From 38092be3e26b70ceca03205ecc8c8c4dff541516 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:56:27 -0700 Subject: [PATCH 31/41] 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 03ded35d7c2..732da3508fb 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4199,6 +4199,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 afba72f7fd34b51ee7b6b0bfc8e72db07ecabc77 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 15:58:14 -0700 Subject: [PATCH 32/41] 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 d7f79f743a99ca27106ceb9a45202b80452b3aee Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 17:14:51 -0700 Subject: [PATCH 33/41] 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 732da3508fb..f80d135b069 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4199,7 +4199,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 ac6dace8a5d476f64b532f9e486f30e713214ea8 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Fri, 29 May 2026 17:42:45 -0700 Subject: [PATCH 34/41] 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 f80d135b069..2fc1579ecb7 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4203,7 +4203,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 4d1e111a7af9d4bcaf18be4569b0b8907c2e7945 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 17:22:45 -0700 Subject: [PATCH 35/41] 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 d41ee6a24fee13ba93c70d677e992e428dfb7a69 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 20:25:06 -0700 Subject: [PATCH 36/41] 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 2fc1579ecb7..97a5d14b681 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -4203,7 +4203,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 f0e13a45a822af9fa42a74fbaab17c4347e8d5a3 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 20:28:27 -0700 Subject: [PATCH 37/41] 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 52008bd57b05efb8b58413551b482ce3101b93f2 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 20:37:13 -0700 Subject: [PATCH 38/41] docs: update Settings.md for MS5525 pitot sensor entry --- docs/Settings.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/Settings.md b/docs/Settings.md index 27e354dc9ce..0de2f3f70d8 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -5946,6 +5946,7 @@ Selection of pitot hardware. VIRTUAL only works if a GPS is enabled. | FAKE | | | MSP | | | DLVR-L10D | | +| MS5525 | | --- From a6f738f54e4efcd86e4a8c2a3aae47961cfd2393 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sat, 30 May 2026 22:24:47 -0700 Subject: [PATCH 39/41] 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 5cc9589002d80250ab47375e4eeba26a459bbe0d Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sun, 31 May 2026 20:04:59 -0700 Subject: [PATCH 40/41] 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 d70f3edb1ca..f6935e31edf 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 d000077fa0bc67ecdd6ba8401c9f56edcea1b314 Mon Sep 17 00:00:00 2001 From: daijoubu Date: Sun, 31 May 2026 20:41:17 -0700 Subject: [PATCH 41/41] 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 f6935e31edf..3df125a1ab2 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4605,7 +4605,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;