Skip to content

Conversation

@daijoubu
Copy link
Contributor

@daijoubu daijoubu commented Feb 6, 2026

Adds support for dronecan to Inav with an initial GPS driver example. Dronecan is implemented using libcanard library.

This is a draft PR to see how what the bot feedback is while waiting for my peripherals to arrive. This has not been flown or tested in HITL yet.
Fixes #11128

  • Test with HITL
  • Test with can current sensor
  • Test with can pwm output
  • Test with can peripheral board
  • Add support for Get/Set parameters Deferred to next PR
  • Add support for logging CAN Rx/Tx errors and bus off events. Deferred to next PR
  • Add documentation

…g messages.

Corrected filters for Rx FIFO and correctly read FIFO level for polling.
…ssages in FIFO at initial check so we don't get stuck in the loop.

Removed interrupt config code in favour of polling the receive FIFO.
daijoubu and others added 20 commits February 6, 2026 17:40
… the MATEKF765SE. Allocate memory for the bxCan write and read messages.
…dle to the CAN instance to avoid a dangling pointer.
…fer and the task reads from the ring buffer.

Fix missing include for math.h
Expand dronecan_messages_unittest.cc from 5 to 14 tests covering
NodeStatus, Fix v1, Auxiliary, boundary values, and data type
verification. Create canard_unittest.cc with 30 tests for the
libcanard core: init/node ID, memory pool, CRC-16/CCITT, float16
conversion, transfer ID logic, DLC conversion, single/multi-frame
TX, RX frame processing, and pool statistics.

Co-Authored-By: Claude Opus 4.6 <[email protected]>
The BatteryInfo message already contains current data which was being
stored in dronecanBattSensorGetAmperage(), but this wasn't integrated
with INAV's battery metering system.

Changes:
- Add CURRENT_SENSOR_CAN enum value in battery_config_structs.h
- Add case handler in battery.c to read current from DroneCAN
- Update settings.yaml to expose CAN option for current_meter_type

Users can now select 'CAN' as the current_meter_type in CLI when using
DroneCAN-compatible battery sensors.

Co-Authored-By: Claude Opus 4.6 <[email protected]>
- Create docs/DroneCAN.md with comprehensive guide covering:
  - Supported features (GPS, battery voltage/current)
  - Configuration settings
  - Hardware setup and wiring
  - Troubleshooting guide
  - Message type reference
- Update docs/Battery.md current_meter_type table to include all
  sensor types (ESC, SMARTPORT, CAN) and link to DroneCAN docs

Co-Authored-By: Claude Opus 4.6 <[email protected]>
The current value from DroneCAN BatteryInfo is in Amps, but INAV's
internal amperage unit is centiamps (0.01A). The conversion was
multiplying by 10 (giving deciamps) instead of 100 (centiamps).

Found during HITL testing: 0.1A applied load showed as 0.01A.

Co-Authored-By: Claude Opus 4.6 <[email protected]>
@daijoubu
Copy link
Contributor Author

HITL Testing Results

Tested on MATEKF765SE with DroneCAN battery monitor.

Phase Passed Skipped
Basic Validation 4 2
Functional Testing 2 3
Robustness Testing 4 2
Stress Testing 3 3
Total 13 16

Skipped tests: No DroneCAN GPS hardware available.

Bug found & fixed: 204ed72c0 - Current reading was 10x too low (multiplied by 10 instead of 100 for centiamp conversion).

Tests passed:

  • Node ID and bitrate configuration
  • Battery discovery, voltage accuracy, current accuracy
  • Low voltage warning integration
  • Hot plug, loss/recovery, bus-off recovery
  • Multiple CAN devices, other CAN traffic

@daijoubu daijoubu marked this pull request as ready for review February 12, 2026 00:32
@daijoubu
Copy link
Contributor Author

I pushed this as ready for review to get feedback from the bots. It is functional at this point but I still want to test with a GPS.

@qodo-code-review
Copy link
Contributor

Review Summary by Qodo

Add DroneCAN support with libcanard library and initial GPS driver

Grey Divider

Walkthroughs

Description
  This description is generated by an AI tool. It may have inaccuracies.
• Adds DroneCAN protocol support to iNav using the libcanard library
• Implements initial GPS driver for DroneCAN devices
• Includes comprehensive DSDL-generated message definitions for DroneCAN and UAVCAN protocols
• Adds DroneCAN driver infrastructure and initialization code
• Includes documentation for DroneCAN support
• Tested with HITL and CAN current sensor
• Resolves issue iNavFlight/inav#11128
• Defers parameter get/set support and CAN error logging to future PRs
Diagram
flowchart LR
  A["iNav Core"] -- "integrates" --> B["DroneCAN Driver"]
  B -- "uses" --> C["libcanard Library"]
  B -- "implements" --> D["GPS Driver"]
  B -- "defines" --> E["DSDL Messages"]
  C -- "handles" --> F["CAN Protocol"]
Loading

Grey Divider

File Changes

Grey Divider

Qodo Logo

@qodo-code-review
Copy link
Contributor

qodo-code-review bot commented Feb 12, 2026

Code Review by Qodo

🐞 Bugs (7) 📘 Rule violations (7) 📎 Requirement gaps (0)

Grey Divider


Action required

1. dsdlc_generated code committed 📘 Rule violation ⛯ Reliability
Description
This PR adds dsdlc_generated DroneCAN DSDL outputs directly to the repo, which are generated
artifacts and can make builds non-reproducible and the repo noisy. These files should be generated
into the build directory (or updated via an explicit opt-in step) and excluded from normal source
tracking.
Code

src/main/drivers/dronecan/dsdlc_generated/src/uavcan.equipment.air_data.Sideslip.c[R1-8]

+#define CANARD_DSDLC_INTERNAL
+#include "uavcan.equipment.air_data.Sideslip.h"
+#include <string.h>
+
+#ifdef CANARD_DSDLC_TEST_BUILD
+#include <test_helpers.h>
+#endif
+
Evidence
Compliance ID 12 forbids committing generated artifacts; the added file is under dsdlc_generated
and contains CANARD_DSDLC_INTERNAL, indicating it is generated output being tracked in the PR.

src/main/drivers/dronecan/dsdlc_generated/src/uavcan.equipment.air_data.Sideslip.c[1-8]
Best Practice: Learned patterns

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
The PR commits DSDL-generated DroneCAN sources/headers under `dsdlc_generated`, which are generated artifacts.
## Issue Context
Generated artifacts should be produced as part of the build (or via an explicit opt-in update command) and not be committed as normal source to keep the repository clean and reproducible.
## Fix Focus Areas
- src/main/drivers/dronecan/dsdlc_generated/src/uavcan.equipment.air_data.Sideslip.c[1-8]
- cmake/main.cmake[2-12]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


2. DataLength used without validation 📘 Rule violation ⛨ Security
Description
The new STM32H7 DroneCAN driver uses RxHeader.DataLength directly for memcpy() into an 8-byte
buffer and also assigns it directly to rx_frame->data_len without checking bounds or converting
DLC-to-length semantics. This can cause out-of-bounds reads/writes or incorrect frame lengths when
the header encoding differs from a raw byte count.
Code

src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[R64-117]

+		rx_frame->data_len = RxHeader.DataLength;
+		memcpy(rx_frame->data, RxData, RxHeader.DataLength);
+
+		// assume a single interface
+		rx_frame->iface_id = 0;
+
+		return 1;
+	}
+
+	// Either no CAN msg to be read, or an error that can be read from hfdcan->ErrorCode
+	return 0;
+}
+
+/**
+  * @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
+  */
+int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) {
+	if (tx_frame == NULL) {
+		return -CANARD_ERROR_INVALID_ARGUMENT;
+	}
+
+	if (tx_frame->id & CANARD_CAN_FRAME_ERR) {
+		return -CANARD_ERROR_INVALID_ARGUMENT; // unsupported frame format
+	}
+
+	FDCAN_TxHeaderTypeDef TxHeader;
+	uint8_t TxData[8];
+
+	// Process canard id to STM FDCAN header format
+	if (tx_frame->id & CANARD_CAN_FRAME_EFF) {
+		TxHeader.IdType = FDCAN_EXTENDED_ID;
+		TxHeader.Identifier = tx_frame->id & CANARD_CAN_EXT_ID_MASK;
+	} else {
+		TxHeader.IdType = FDCAN_STANDARD_ID;
+		TxHeader.Identifier = tx_frame->id & CANARD_CAN_STD_ID_MASK;
+	}
+
+	TxHeader.DataLength = tx_frame->data_len;
+
+	if (tx_frame->id & CANARD_CAN_FRAME_RTR) {
+		TxHeader.TxFrameType = FDCAN_REMOTE_FRAME;
+	} else {
+		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
+	memcpy(TxData, tx_frame->data, TxHeader.DataLength);
Evidence
Compliance ID 9 requires validating external payload lengths before reading/copying; the code copies
RxHeader.DataLength bytes into a fixed 8-byte buffer and similarly uses tx_frame->data_len as
the HAL DataLength without validation/conversion.

src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[64-65]
src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[104-117]
Best Practice: Learned patterns

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
`RxHeader.DataLength`/`TxHeader.DataLength` are used as raw byte counts for `memcpy()` without conversion or bounds checks, risking buffer overruns or invalid CAN frames.
## Issue Context
These values may be DLC-encoded or otherwise not guaranteed to be &amp;amp;amp;lt;= 8; even if classic CAN is intended, defensive checks are required for external inputs.
## Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[64-65]
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[104-117]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


3. canardSTM32ComputeTimings unchecked 📘 Rule violation ⛯ Reliability
Description
canardSTM32ComputeTimings() returns bool but its result is ignored and out_timings is used
unconditionally to configure the peripheral. If timing computation fails, CAN may be initialized
with invalid/uninitialized timing values without any error propagation.
Code

src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[R162-168]

+  canardSTM32ComputeTimings(bitrate, &out_timings);
+
+  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);
Evidence
Compliance ID 3 requires handling failure points; the timing computation has a failure return but
the caller does not check it and proceeds using out_timings.

Rule 3: Generic: Robust Error Handling and Edge Case Management
src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[162-168]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
CAN timing computation failure is ignored, potentially configuring hardware with invalid values.
## Issue Context
The timing helper explicitly returns `false` for invalid/unsatisfied configurations; initialization should not proceed on failure.
## Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[162-168]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


View more (7)
4. canardSTM32CAN1_Init() return ignored 📘 Rule violation ⛯ Reliability
Description
canardSTM32CAN1_Init() returns a status code but dronecanInit() ignores it and continues
initialization. This can leave DroneCAN partially initialized and failing silently at runtime.
Code

src/main/drivers/dronecan/dronecan.c[R422-439]

+    canardSTM32CAN1_Init(bitrate);  // TODO: Handle error and disable CAN if this call fails.
+    /*
+    Initializing the Libcanard instance.
+    */
+    LOG_DEBUG(CAN, "canardInit");
+    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");
Evidence
Compliance ID 3 requires handling potential failure points; the CAN init call is explicitly marked
with a TODO to handle errors but currently continues regardless of init outcome.

Rule 3: Generic: Robust Error Handling and Edge Case Management
src/main/drivers/dronecan/dronecan.c[422-423]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
DroneCAN initialization ignores CAN peripheral init failures.
## Issue Context
Proceeding after failed CAN init can cause confusing runtime behavior and make debugging difficult.
## Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[404-440]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


5. dronecan.h missing deps 🐞 Bug ✓ Correctness
Description
dronecan.h uses PG_DECLARE but doesn’t include config/parameter_group.h (and lacks a header
guard), making builds depend on include order. fc_tasks.c includes dronecan.h before any header
that defines PG_DECLARE, which can cause compile failures.
Code

src/main/drivers/dronecan/dronecan.h[R1-19]

+#include "common/time.h"
+
+void dronecanInit(void);
+void dronecanUpdate(timeUs_t currentTimeUs);
+
+typedef enum {
+    DRONECAN_BITRATE_125KBPS = 0,
+    DRONECAN_BITRATE_250KBPS,
+    DRONECAN_BITRATE_500KBPS,
+    DRONECAN_BITRATE_1000KBPS,
+    DRONECAN_BITRATE_COUNT
+} dronecanBitrate_e;
+
+typedef struct dronecanConfig_s {
+    uint8_t nodeID;
+    dronecanBitrate_e bitRateKbps;
+} dronecanConfig_t;
+
+PG_DECLARE(dronecanConfig_t, dronecanConfig);
Evidence
PG_DECLARE is defined in config/parameter_group.h, but dronecan.h does not include it;
fc_tasks.c includes dronecan.h directly among its early includes, before any inclusion of
config/parameter_group.h in that unit.

src/main/drivers/dronecan/dronecan.h[1-19]
src/main/config/parameter_group.h[104-110]
src/main/fc/fc_tasks.c[18-43]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
`src/main/drivers/dronecan/dronecan.h` is not self-contained: it uses `PG_DECLARE` but does not include the header that defines it (`config/parameter_group.h`). This creates brittle include-order dependencies and can break compilation in files that include `dronecan.h` early (e.g. `fc_tasks.c`).
### Issue Context
`PG_DECLARE` is defined in `src/main/config/parameter_group.h`. Some compilation units include `dronecan.h` before any header that brings in `parameter_group.h`.
### Fix Focus Areas
- src/main/drivers/dronecan/dronecan.h[1-19]
- src/main/fc/fc_tasks.c[18-43]
- src/main/config/parameter_group.h[104-110]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


6. PG_ID_LAST excludes DroneCAN 🐞 Bug ✓ Correctness
Description
PG_DRONECAN_CONFIG is defined but PG_INAV_END/PG_ID_LAST is not updated, so DroneCAN config is
outside the enumerated PG range. MSP parameter group enumeration uses PG_ID_LAST, so tools won’t
discover DroneCAN parameters.
Code

src/main/config/parameter_group_ids.h[R135-138]

+#define PG_DRONECAN_CONFIG 1045
#define PG_INAV_END PG_GEOZONE_VERTICES
// OSD configuration (subject to change)
Evidence
PG_DRONECAN_CONFIG is 1045 but PG_INAV_END remains PG_GEOZONE_VERTICES (1044), and
PG_ID_LAST is defined as PG_INAV_END. MSP enumerates parameter groups using the inclusive range
[PG_ID_FIRST..PG_ID_LAST], so 1045 is skipped.

src/main/config/parameter_group_ids.h[132-150]
src/main/fc/fc_msp.c[3899-3919]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
`PG_DRONECAN_CONFIG` is outside the `[PG_ID_FIRST..PG_ID_LAST]` range because `PG_INAV_END` wasn’t updated. This prevents MSP parameter-group enumeration from reporting DroneCAN config.
### Issue Context
MSP uses `PG_ID_FIRST`/`PG_ID_LAST` to enumerate parameter groups.
### Fix Focus Areas
- src/main/config/parameter_group_ids.h[132-150]
- src/main/fc/fc_msp.c[3899-3919]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


7. TX queue popped on failure 🐞 Bug ⛯ Reliability
Description
processCanardTxQueue() always pops the libcanard TX queue even when canardSTM32Transmit()
returns 0 (not sent, e.g. TX FIFO full). This will silently drop DroneCAN frames under load.
Code

src/main/drivers/dronecan/dronecan.c[R358-375]

+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);
+		} else if (tx_res > 0) {
+			// LOG_DEBUG(CAN, "Successfully transmitted message");
+		}
+        else
+        {
+            LOG_DEBUG(CAN, "hfderror transmitting.");
+        }
+		// Pop canardTxQueue either way
+		canardPopTxQueue(&canard);
+	}
Evidence
The platform TX function explicitly returns 0 on failure (e.g. H7 HAL_FDCAN_AddMessageToTxFifoQ
fails). processCanardTxQueue() pops the queue “either way”, which discards unsent frames instead
of retrying later.

src/main/drivers/dronecan/dronecan.c[358-375]
src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[119-128]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
`processCanardTxQueue()` drops frames by popping the TX queue even when the hardware transmit reports “not sent yet” (return 0).
### Issue Context
On STM32H7 the transmit function returns 0 when `HAL_FDCAN_AddMessageToTxFifoQ` fails (e.g. TX FIFO full), which should be retried.
### Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[358-375]
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[83-128]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


✅ 8. F7 transmit always succeeds 🐞 Bug ✓ Correctness
Description
On STM32F7, canardSTM32Transmit() returns 1 even when HAL_CAN_Transmit() fails, masking errors
and causing upper layers to believe the frame was sent.
Code

src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[R160-170]

+	returnCode = HAL_CAN_Transmit(&hcan1, 100);
+    if( returnCode == HAL_OK) {
+		// LOG_DEBUG(CAN, "Successfully sent message with id: %lu", tx_frame->id);
+		return 1;
+	}
+
+	LOG_DEBUG(CAN, "Failed at adding message with id: %lu to Tx Queue.  Error: %lu", tx_frame->id, returnCode);
+    
+	// This might be for many reasons including the Tx Fifo being full, the error can be read from hfdcan->ErrorCode
+	return 1;
+}
Evidence
The function logs a failure but still returns 1, which is indistinguishable from success for callers
like processCanardTxQueue().

src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[160-170]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
STM32F7 `canardSTM32Transmit()` reports success even on HAL transmit failure, hiding errors and causing silent packet loss.
### Issue Context
Callers use the return value to decide whether to keep or drop frames.
### Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[127-170]
- src/main/drivers/dronecan/dronecan.c[358-375]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


✅ 9. RX loop skips messages 🐞 Bug ✓ Correctness
Description
The DroneCAN RX processing loop decrements numMessagesToProcess twice (in the for header and
inside the body), which will process only roughly half the queued frames and can starve RX under
load.
Code

src/main/drivers/dronecan/dronecan.c[R462-477]

+             for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--)
+             {
+                 //LOG_DEBUG(CAN, "Received a message");
+                 //LOG_DEBUG(CAN, "Rx FIFO Fill Level: %lu", canardSTM32GetRxFifoFillLevel());
+	            timestamp = HAL_GetTick() * 1000ULL;
+	            rx_res = canardSTM32Recieve(&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);
+	             }
+                 numMessagesToProcess--;
+             }
Evidence
The counter is decremented once by the for (...; ...; numMessagesToProcess--) and again via
numMessagesToProcess--; inside the loop, reducing iterations and skipping messages.

src/main/drivers/dronecan/dronecan.c[462-477]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
The RX loop decrements its loop counter twice, causing it to skip frames.
### Issue Context
`canardSTM32GetRxFifoFillLevel()` is used to determine how many frames to process.
### Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[462-477]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


10. F7 unique ID collision 🐞 Bug ✓ Correctness
Description
STM32F7 canardSTM32GetUniqueID() uses HAL_GetDEVID() (device type ID), not the MCU unique ID, so
multiple F7 devices will report identical IDs on the bus. This breaks NodeInfo uniqueness
assumptions and can break DNA/identification workflows.
Code

src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[R433-440]

+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_GetDEVID();
+    HALUniqueIDs[1] = 0;
+    HALUniqueIDs[2] = 0;
+    memcpy(id, HALUniqueIDs, 12);
Evidence
The F7 implementation populates the ID with HAL_GetDEVID() and zeros, which is not unique per
chip. The H7 implementation uses HAL_GetUIDw0/1/2(), demonstrating the intended approach.

src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[433-441]
src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[388-395]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
STM32F7 unique ID generation is not unique, causing collisions between devices.
### Issue Context
DroneCAN node identification expects a stable per-device unique ID.
### Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[430-441]
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[388-395]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools



Remediation recommended

✅ 11. Decode failures return silently 📘 Rule violation ✓ Correctness
Description
Multiple DroneCAN handlers drop messages by returning immediately when *_decode() fails without
logging or any other error signal. This creates silent failures that are hard to diagnose in-field.
Code

src/main/drivers/dronecan/dronecan.c[R51-115]

+	if (uavcan_protocol_NodeStatus_decode(transfer, &nodeStatus)) {
+		return;
+	}
+
+	// LOG_DEBUG(CAN, "Node Health ");
+
+	switch (nodeStatus.health) {
+	case UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK:
+		// LOG_DEBUG(CAN, "OK");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_HEALTH_WARNING:
+		// LOG_DEBUG(CAN, "WARNING");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_HEALTH_ERROR:
+		// LOG_DEBUG(CAN, "ERROR");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_HEALTH_CRITICAL:
+		// LOG_DEBUG(CAN, "CRITICAL");
+		break;
+	default:
+		// LOG_DEBUG(CAN, "UNKNOWN?");
+		break;
+	}
+
+	// LOG_DEBUG(CAN, "Node Mode ");
+
+	switch(nodeStatus.mode) {
+	case UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL:
+		// LOG_DEBUG(CAN, "OPERATIONAL");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION:
+		// LOG_DEBUG(CAN, "INITIALIZATION");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE:
+		// LOG_DEBUG(CAN, "MAINTENANCE");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_MODE_SOFTWARE_UPDATE:
+		// LOG_DEBUG(CAN, "SOFTWARE UPDATE");
+		break;
+	case UAVCAN_PROTOCOL_NODESTATUS_MODE_OFFLINE:
+		// LOG_DEBUG(CAN, "OFFLINE");
+		break;
+	default:
+		// LOG_DEBUG(CAN, "UNKNOWN?");
+		break;
+	}
+}
+
+void handle_GNSSAuxiliary(CanardInstance *ins, CanardRxTransfer *transfer) {
+	UNUSED(ins);
+    struct uavcan_equipment_gnss_Auxiliary gnssAuxiliary;
+
+	if (uavcan_equipment_gnss_Auxiliary_decode(transfer, &gnssAuxiliary)) {
+		return;
+	}
+    LOG_DEBUG(CAN, "GNSS Auxiliary: Num Sats: %d, HDOP %.2f", gnssAuxiliary.sats_used, (double)gnssAuxiliary.hdop);
+}
+
+void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) {
+	UNUSED(ins);
+    struct uavcan_equipment_gnss_Fix gnssFix;
+
+	if (uavcan_equipment_gnss_Fix_decode(transfer, &gnssFix)) {
+		return;
+	}
Evidence
Compliance ID 3 forbids silent failures/ignored errors; the new handlers discard failed decodes with
return; and provide no context about which message failed or why.

Rule 3: Generic: Robust Error Handling and Edge Case Management
src/main/drivers/dronecan/dronecan.c[51-53]
src/main/drivers/dronecan/dronecan.c[113-115]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
Decode failures are silently ignored, making it difficult to detect malformed frames or schema mismatches.
## Issue Context
This is a new external-input path (CAN bus) where malformed payloads are expected; diagnostics should be available without flooding logs.
## Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[47-129]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


✅ 12. GNSS logs expose coordinates 📘 Rule violation ⛨ Security
Description
The new debug logging prints raw GPS latitude/longitude values, which can be sensitive location
data, and uses unstructured log strings. This may violate secure logging requirements and makes
automated log analysis harder.
Code

src/main/drivers/dronecan/dronecan.c[R106-135]

+    LOG_DEBUG(CAN, "GNSS Auxiliary: Num Sats: %d, HDOP %.2f", gnssAuxiliary.sats_used, (double)gnssAuxiliary.hdop);
+}
+
+void handle_GNSSFix(CanardInstance *ins, CanardRxTransfer *transfer) {
+	UNUSED(ins);
+    struct uavcan_equipment_gnss_Fix gnssFix;
+
+	if (uavcan_equipment_gnss_Fix_decode(transfer, &gnssFix)) {
+		return;
+	}
+    dronecanGPSReceiveGNSSFix(&gnssFix);
+    LOG_DEBUG(CAN, "GNSS Fix: Longitude: %lld, Latitude %lld", gnssFix.longitude_deg_1e8, gnssFix.latitude_deg_1e8);
+}
+
+void handle_GNSSFix2(CanardInstance *ins, CanardRxTransfer *transfer) {
+	UNUSED(ins);
+    struct uavcan_equipment_gnss_Fix2 gnssFix2;
+
+	if (uavcan_equipment_gnss_Fix2_decode(transfer, &gnssFix2)) {
+		return;
+	}
+    dronecanGPSReceiveGNSSFix2(&gnssFix2);
+    LOG_DEBUG(CAN, "GNSS Fix2: Longitude: %lld, Latitude %lld", gnssFix2.longitude_deg_1e8, gnssFix2.latitude_deg_1e8);
+}
+
+void handle_GNSSRCTMStream(CanardInstance *ins, CanardRxTransfer *transfer) {
+	UNUSED(ins);
+    struct uavcan_equipment_gnss_RTCMStream gnssRTCMStream;
+
+	if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &gnssRTCMStream)) {
Evidence
Compliance ID 5 requires avoiding sensitive data in logs and using structured logging; the added
LOG_DEBUG() lines emit raw GNSS coordinates in free-form strings.

Rule 5: Generic: Secure Logging Practices
src/main/drivers/dronecan/dronecan.c[106-107]
src/main/drivers/dronecan/dronecan.c[117-118]
src/main/drivers/dronecan/dronecan.c[128-129]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
Logs include raw GNSS coordinates and unstructured strings.
## Issue Context
Location data can be sensitive; logs should avoid detailed location output by default and be machine-parseable where possible.
## Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[99-135]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


13. 377-byte stack buffer used 📘 Rule violation ⛯ Reliability
Description
handle_GetNodeInfo() and send_NodeStatus() allocate `uint8_t
buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE]` on the stack, where the max is 377 bytes. In
embedded/IO paths this increases stack pressure and risk of overflow, especially if called in
constrained task contexts.
Code

src/main/drivers/dronecan/dronecan.c[R158-205]

+	printf("GetNodeInfo request from %d", transfer->source_node_id);
+
+	uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
+	struct uavcan_protocol_GetNodeInfoResponse pkt;
+
+	memset(&pkt, 0, sizeof(pkt));
+
+	node_status.uptime_sec = HAL_GetTick() / 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 = 0; // shortGitRevision; // 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);
+
+	canardRequestOrRespond(ins,
+						   transfer->source_node_id,
+						   UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,
+						   UAVCAN_PROTOCOL_GETNODEINFO_ID,
+						   &transfer->transfer_id,
+						   transfer->priority,
+						   CanardResponse,
+						   &buffer[0],
+						   total_size);
+}
+
+// Canard Senders
+
+/*
+  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) {
+    uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];
+
Evidence
Compliance ID 13 recommends avoiding large stack buffers in sensitive embedded/IO paths; the PR
introduces 377-byte stack allocations in message handlers/senders.

src/main/drivers/dronecan/dsdlc_generated/include/uavcan.protocol.GetNodeInfo_res.h[10-16]
src/main/drivers/dronecan/dronecan.c[158-161]
src/main/drivers/dronecan/dronecan.c[203-205]
Best Practice: Learned patterns

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
Large stack buffers are allocated in DroneCAN handler/sender paths, increasing stack pressure.
## Issue Context
Embedded systems often have small stacks per task/ISR; using static/shared buffers or preallocated pools is safer.
## Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[158-205]
- src/main/drivers/dronecan/dsdlc_generated/include/uavcan.protocol.GetNodeInfo_res.h[10-16]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


View more (1)
✅ 14. 1Hz tasks spam post-boot 🐞 Bug ➹ Performance
Description
next_1hz_service_at starts at 0 and is updated using += 1000000, so for approximately the first
second after boot (or after a long pause), process1HzTasks() will run on every DroneCAN scheduler
tick rather than at 1Hz.
Code

src/main/drivers/dronecan/dronecan.c[R445-483]

+    static timeUs_t next_1hz_service_at = 0;
+    static timeUs_t busoffTimeUs = 0;
+    CanardCANFrame rx_frame;
+    int numMessagesToProcess = 0;
+    static enum dronecanState_e dronecanState = STATE_DRONECAN_INIT;
+    canardProtocolStatus_t protocolStatus = {};
+    uint64_t timestamp;
+    int16_t rx_res;
+
+    switch(dronecanState) {
+        case STATE_DRONECAN_INIT:
+            dronecanState = STATE_DRONECAN_NORMAL;
+            break;
+
+        case STATE_DRONECAN_NORMAL:
+            processCanardTxQueue();
+
+             for (numMessagesToProcess = canardSTM32GetRxFifoFillLevel(); numMessagesToProcess > 0; numMessagesToProcess--)
+             {
+                 //LOG_DEBUG(CAN, "Received a message");
+                 //LOG_DEBUG(CAN, "Rx FIFO Fill Level: %lu", canardSTM32GetRxFifoFillLevel());
+	            timestamp = HAL_GetTick() * 1000ULL;
+	            rx_res = canardSTM32Recieve(&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);
+	             }
+                 numMessagesToProcess--;
+             }
+            if (currentTimeUs >= next_1hz_service_at)
+            {
+		        next_1hz_service_at += 1000000ULL;
+		        process1HzTasks(currentTimeUs);
+        
+            }
Evidence
With next_1hz_service_at == 0, the if (currentTimeUs >= next_1hz_service_at) condition is true
on the first many calls until next_1hz_service_at catches up past currentTimeUs via repeated `+=
1000000` increments.

src/main/drivers/dronecan/dronecan.c[445-483]

Agent prompt
The issue below was found during a code review. Follow the provided context and guidance below and implement a solution

## Issue description
The 1Hz scheduler gate runs too frequently right after boot because `next_1hz_service_at` starts at zero and is advanced via `+=`.
### Issue Context
This causes NodeStatus transmission and stale-transfer cleanup to run far more often than intended immediately after startup.
### Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[445-483]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools


Grey Divider

ⓘ The new review experience is currently in Beta. Learn more

Grey Divider

Qodo Logo

Comment on lines +1 to +8
#define CANARD_DSDLC_INTERNAL
#include "uavcan.equipment.air_data.Sideslip.h"
#include <string.h>

#ifdef CANARD_DSDLC_TEST_BUILD
#include <test_helpers.h>
#endif

Copy link
Contributor

Choose a reason for hiding this comment

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

Action required

1. dsdlc_generated code committed 📘 Rule violation ⛯ Reliability

This PR adds dsdlc_generated DroneCAN DSDL outputs directly to the repo, which are generated
artifacts and can make builds non-reproducible and the repo noisy. These files should be generated
into the build directory (or updated via an explicit opt-in step) and excluded from normal source
tracking.
Agent Prompt
## Issue description
The PR commits DSDL-generated DroneCAN sources/headers under `dsdlc_generated`, which are generated artifacts.

## Issue Context
Generated artifacts should be produced as part of the build (or via an explicit opt-in update command) and not be committed as normal source to keep the repository clean and reproducible.

## Fix Focus Areas
- src/main/drivers/dronecan/dsdlc_generated/src/uavcan.equipment.air_data.Sideslip.c[1-8]
- cmake/main.cmake[2-12]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools

Comment on lines +64 to +117
rx_frame->data_len = RxHeader.DataLength;
memcpy(rx_frame->data, RxData, RxHeader.DataLength);

// assume a single interface
rx_frame->iface_id = 0;

return 1;
}

// Either no CAN msg to be read, or an error that can be read from hfdcan->ErrorCode
return 0;
}

/**
* @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
*/
int16_t canardSTM32Transmit(const CanardCANFrame* const tx_frame) {
if (tx_frame == NULL) {
return -CANARD_ERROR_INVALID_ARGUMENT;
}

if (tx_frame->id & CANARD_CAN_FRAME_ERR) {
return -CANARD_ERROR_INVALID_ARGUMENT; // unsupported frame format
}

FDCAN_TxHeaderTypeDef TxHeader;
uint8_t TxData[8];

// Process canard id to STM FDCAN header format
if (tx_frame->id & CANARD_CAN_FRAME_EFF) {
TxHeader.IdType = FDCAN_EXTENDED_ID;
TxHeader.Identifier = tx_frame->id & CANARD_CAN_EXT_ID_MASK;
} else {
TxHeader.IdType = FDCAN_STANDARD_ID;
TxHeader.Identifier = tx_frame->id & CANARD_CAN_STD_ID_MASK;
}

TxHeader.DataLength = tx_frame->data_len;

if (tx_frame->id & CANARD_CAN_FRAME_RTR) {
TxHeader.TxFrameType = FDCAN_REMOTE_FRAME;
} else {
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
memcpy(TxData, tx_frame->data, TxHeader.DataLength);
Copy link
Contributor

Choose a reason for hiding this comment

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

Action required

2. datalength used without validation 📘 Rule violation ⛨ Security

The new STM32H7 DroneCAN driver uses RxHeader.DataLength directly for memcpy() into an 8-byte
buffer and also assigns it directly to rx_frame->data_len without checking bounds or converting
DLC-to-length semantics. This can cause out-of-bounds reads/writes or incorrect frame lengths when
the header encoding differs from a raw byte count.
Agent Prompt
## Issue description
`RxHeader.DataLength`/`TxHeader.DataLength` are used as raw byte counts for `memcpy()` without conversion or bounds checks, risking buffer overruns or invalid CAN frames.

## Issue Context
These values may be DLC-encoded or otherwise not guaranteed to be <= 8; even if classic CAN is intended, defensive checks are required for external inputs.

## Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[64-65]
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[104-117]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools

Comment on lines +162 to +168
canardSTM32ComputeTimings(bitrate, &out_timings);

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);
Copy link
Contributor

Choose a reason for hiding this comment

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

Action required

3. canardstm32computetimings unchecked 📘 Rule violation ⛯ Reliability

canardSTM32ComputeTimings() returns bool but its result is ignored and out_timings is used
unconditionally to configure the peripheral. If timing computation fails, CAN may be initialized
with invalid/uninitialized timing values without any error propagation.
Agent Prompt
## Issue description
CAN timing computation failure is ignored, potentially configuring hardware with invalid values.

## Issue Context
The timing helper explicitly returns `false` for invalid/unsatisfied configurations; initialization should not proceed on failure.

## Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[162-168]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools

Comment on lines +422 to +439
canardSTM32CAN1_Init(bitrate); // TODO: Handle error and disable CAN if this call fails.
/*
Initializing the Libcanard instance.
*/
LOG_DEBUG(CAN, "canardInit");
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");
Copy link
Contributor

Choose a reason for hiding this comment

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

Action required

4. canardstm32can1_init() return ignored 📘 Rule violation ⛯ Reliability

canardSTM32CAN1_Init() returns a status code but dronecanInit() ignores it and continues
initialization. This can leave DroneCAN partially initialized and failing silently at runtime.
Agent Prompt
## Issue description
DroneCAN initialization ignores CAN peripheral init failures.

## Issue Context
Proceeding after failed CAN init can cause confusing runtime behavior and make debugging difficult.

## Fix Focus Areas
- src/main/drivers/dronecan/dronecan.c[404-440]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools

Comment on lines 433 to 440
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_GetDEVID();
HALUniqueIDs[1] = 0;
HALUniqueIDs[2] = 0;
memcpy(id, HALUniqueIDs, 12);
Copy link
Contributor

Choose a reason for hiding this comment

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

Action required

10. F7 unique id collision 🐞 Bug ✓ Correctness

STM32F7 canardSTM32GetUniqueID() uses HAL_GetDEVID() (device type ID), not the MCU unique ID, so
multiple F7 devices will report identical IDs on the bus. This breaks NodeInfo uniqueness
assumptions and can break DNA/identification workflows.
Agent Prompt
### Issue description
STM32F7 unique ID generation is not unique, causing collisions between devices.

### Issue Context
DroneCAN node identification expects a stable per-device unique ID.

### Fix Focus Areas
- src/main/drivers/dronecan/libcanard/canard_stm32f7xx_driver.c[430-441]
- src/main/drivers/dronecan/libcanard/canard_stm32h7xx_driver.c[388-395]

ⓘ Copy this prompt and use it to remediate the issue with your preferred AI generation tools

daijoubu and others added 3 commits February 11, 2026 17:13
Fixes from Qodo code review:

1. RX loop double decrement - removed extra numMessagesToProcess--
   that caused half of received messages to be skipped

2. TX queue pop on failure - only pop queue on success (ret > 0),
   break loop on FIFO full (ret == 0) to retry later

3. F7 transmit return value - return 0 on HAL failure instead of 1,
   so caller knows transmission failed

4. F7 unique ID - use HAL_GetUIDw0/1/2() instead of HAL_GetDEVID()
   to get actual per-chip unique ID

5. PG_INAV_END - update to PG_DRONECAN_CONFIG so DroneCAN params
   are discoverable via MSP parameter group enumeration

6. dronecan.h - add #pragma once and include parameter_group.h
   to make header self-contained

7. 1Hz timer init - initialize next_1hz_service_at in INIT state
   to prevent spam at boot

Co-Authored-By: Claude Opus 4.6 <[email protected]>
…_GetUIDwX functions. Updating the HAL is a future project.
Address remaining Qodo code review items:

1. Add LOG_DEBUG for decode failures - all message handlers now log
   when decoding fails, making debugging easier

2. Remove GPS coordinate logging - replaced lat/lon logging with
   simple "GNSS Fix received" to avoid exposing sensitive location
   data in debug logs

3. Fix send_NodeStatus buffer size - use NODESTATUS_MAX_SIZE (7)
   instead of GETNODEINFO_RESPONSE_MAX_SIZE (377) to reduce stack
   pressure in this frequently-called function

Co-Authored-By: Claude Opus 4.6 <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant