-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Add support for dronecan and initial GPS driver #11313
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: maintenance-10.x
Are you sure you want to change the base?
Conversation
…up Node States message at 1 Hz.
Set Node Status to real data.
…apted for c from https://github.com/ArduPilot/ardupilot/blob/4f4457d259c54bff9a7d909c71e471f7cf1ef8d9/libraries/AP_HAL_ChibiOS/CanIface.cpp Remove redundant call to enable FDCAN clock.
…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.
…driver support on the STM32Fxxx series.
…ALs do not support it.
… 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]>
…e Claude forgot to.
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]>
HITL Testing ResultsTested on MATEKF765SE with DroneCAN battery monitor.
Skipped tests: No DroneCAN GPS hardware available. Bug found & fixed: Tests passed:
|
|
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. |
Review Summary by QodoAdd DroneCAN support with libcanard library and initial GPS driver WalkthroughsDescriptionThis 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 Diagramflowchart 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"]
File Changes |
Code Review by Qodo
1. dsdlc_generated code committed
|
| #define CANARD_DSDLC_INTERNAL | ||
| #include "uavcan.equipment.air_data.Sideslip.h" | ||
| #include <string.h> | ||
|
|
||
| #ifdef CANARD_DSDLC_TEST_BUILD | ||
| #include <test_helpers.h> | ||
| #endif | ||
|
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
| 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); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
| 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); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
| 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"); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
| 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); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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
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]>
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
Add support for Get/Set parametersDeferred to next PRAdd support for logging CAN Rx/Tx errors and bus off events.Deferred to next PR