Skip to content

Add CRSF sensor input on dedicated UART#11379

Open
sensei-hacker wants to merge 1 commit intoiNavFlight:maintenance-9.xfrom
sensei-hacker:feature-crsf-sensor-input
Open

Add CRSF sensor input on dedicated UART#11379
sensei-hacker wants to merge 1 commit intoiNavFlight:maintenance-9.xfrom
sensei-hacker:feature-crsf-sensor-input

Conversation

@sensei-hacker
Copy link
Member

@sensei-hacker sensei-hacker commented Mar 1, 2026

Summary

Add support for receiving sensor data from CRSF-speaking devices connected to a dedicated flight controller UART. Incoming CRSF frames are parsed and fed into INAV's real sensor subsystems, making the data automatically available to OSD, blackbox, navigation, and outgoing CRSF telemetry.

Supported Sensors

  • GPS (0x02): New GPS_CRSF provider — feeds gpsSolDRV like MSP GPS
  • Barometer (0x09): New BARO_CRSF driver — converts altitude to pressure via ISA formula
  • Battery (0x08): New CRSF voltage/current source — follows SmartPort integration pattern
  • Vario (0x07): Stored and used as preferred source for outgoing CRSF vario telemetry

Configuration

serial <n> 16777216 420000 0 0 0
set gps_provider = CRSF
set baro_hardware = CRSF
set vbat_meter_type = CRSF
set current_meter_type = CRSF
save

Changes

  • New FUNCTION_CRSF_SENSOR serial function (repurposes FUNCTION_UNUSED_2, bit 24)
  • New files: crsf_sensor.c/h, gps_crsf.c, barometer_crsf.c/h, battery_sensor_crsf.c/h
  • ISR assembles frames, scheduler task dispatches — follows existing CRSF RX pattern
  • GPS/baro/battery feed real subsystems; vario modifies outgoing telemetry frame
  • Gated on MCU_FLASH_SIZE > 512 to exclude F722 and other flash-constrained targets

Known Limitations

  • CRSF GPS provides no NED velocity or accuracy data — flags set accordingly
  • Baro altitude-to-pressure conversion assumes ISA standard atmosphere
  • Vario passthrough only affects outgoing CRSF telemetry (not position estimator)
  • Configurator will need a corresponding update to show the new serial function

Add support for receiving sensor data from CRSF-speaking devices
connected to a dedicated flight controller UART, similar to MSP
sensor input. Incoming CRSF frames are parsed and dispatched to
INAV's real sensor subsystems so the data is automatically available
to OSD, blackbox, navigation, and outgoing CRSF telemetry.

Supported sensor types:
- GPS (0x02): New GPS_CRSF provider feeding gpsSolDRV
- Barometer (0x09): New BARO_CRSF driver with altitude-to-pressure
  conversion via ISA formula
- Battery (0x08): New CRSF voltage/current source following the
  SmartPort integration pattern
- Vario (0x07): Stored and used as preferred source for outgoing
  CRSF vario telemetry frames

Configuration:
  serial <n> 16777216 420000 0 0 0
  set gps_provider = CRSF
  set baro_hardware = CRSF
  set vbat_meter_type = CRSF
  set current_meter_type = CRSF

Feature is gated on MCU_FLASH_SIZE > 512 to exclude F722 and other
flash-constrained targets.
@sensei-hacker sensei-hacker added hardware needed Blocked by lack of hardware to reproduce issue Testing Required Requires Configurator Experimental and removed hardware needed Blocked by lack of hardware to reproduce issue labels Mar 1, 2026
@wimalopaan
Copy link

wimalopaan commented Mar 2, 2026

Just tested RM ERS CU 01. At a first quick glance it works ;-) Will test the other sensors too if there is more time, and report back.
Thank you very much!!!
Great work!

@wimalopaan
Copy link

wimalopaan commented Mar 2, 2026

Just an idea: would it also be possible to support the ERS CV01 cells voltages sensors?
For ids < 128 this may simple a passthru as cells voltages, for ids >= 128 (batt voltages) this may be the same integration in the INav sensor collection as with batt sensor. ELRS just took a similar approach.

@wimalopaan
Copy link

One additional observation: according to my knowledge the Radiomaster Sensor Configuration LUA sends MSP-over-CRSF messages as we discussed earlier. I also traced the tx-line of the FC uart where the sensors are connected. The tx-line is permanently low and no messages show up here.

I think I missed the configuration of INav to forward the MSP-over-CRSF to the port the sensors are connected. How should I enable that?

This is needed e.g. to query some parameters of the sensors or e.g. to set the capacity, set the Led or start the calibration of the baro sensor.
This is also required e.g. for the RPM sensor to set the PP, but this isn't covered here anyway, so don't bother with that.

@sensei-hacker sensei-hacker marked this pull request as ready for review March 2, 2026 14:54
@qodo-code-review
Copy link
Contributor

Review Summary by Qodo

Add CRSF sensor input on dedicated UART with multi-sensor support

Grey Divider

Walkthroughs

Description
• Add CRSF sensor input on dedicated UART with frame parsing
• Support GPS, barometer, battery, and vario sensor data integration
• Feed parsed sensor data into INAV's real subsystems automatically
• Gate feature on MCU_FLASH_SIZE > 512 to exclude flash-constrained targets
Diagram
flowchart LR
  CRSF["CRSF Device"]
  UART["Dedicated UART"]
  ISR["ISR Frame Assembly"]
  TASK["Scheduler Task"]
  GPS["GPS Provider"]
  BARO["Barometer Driver"]
  BATT["Battery Sensor"]
  VARIO["Vario Storage"]
  CRSF -->|"420kbaud"| UART
  UART -->|"crsfSensorDataReceive"| ISR
  ISR -->|"crsfSensorFrameDone"| TASK
  TASK -->|"crsfSensorDispatchFrame"| GPS
  TASK -->|"crsfSensorDispatchFrame"| BARO
  TASK -->|"crsfSensorDispatchFrame"| BATT
  TASK -->|"crsfSensorDispatchFrame"| VARIO
Loading

Grey Divider

File Changes

1. src/main/io/crsf_sensor.c New feature +321/-0

Core CRSF sensor frame parsing and dispatch

src/main/io/crsf_sensor.c


2. src/main/io/crsf_sensor.h New feature +35/-0

CRSF sensor input public API definitions

src/main/io/crsf_sensor.h


3. src/main/drivers/barometer/barometer_crsf.c New feature +109/-0

CRSF barometer driver with ISA altitude conversion

src/main/drivers/barometer/barometer_crsf.c


View more (19)
4. src/main/drivers/barometer/barometer_crsf.h New feature +29/-0

CRSF barometer driver header and interface

src/main/drivers/barometer/barometer_crsf.h


5. src/main/io/gps_crsf.c New feature +56/-0

CRSF GPS provider implementation and data handling

src/main/io/gps_crsf.c


6. src/main/sensors/battery_sensor_crsf.c New feature +72/-0

CRSF battery sensor voltage and current storage

src/main/sensors/battery_sensor_crsf.c


7. src/main/sensors/battery_sensor_crsf.h New feature +32/-0

CRSF battery sensor public interface definitions

src/main/sensors/battery_sensor_crsf.h


8. src/main/io/gps.c ✨ Enhancement +7/-0

Add GPS_CRSF provider to GPS provider descriptor table

src/main/io/gps.c


9. src/main/io/gps.h ✨ Enhancement +1/-0

Add GPS_CRSF enum value to gpsProvider_e

src/main/io/gps.h


10. src/main/io/gps_private.h ✨ Enhancement +4/-0

Add CRSF GPS function declarations to private header

src/main/io/gps_private.h


11. src/main/sensors/barometer.c ✨ Enhancement +15/-0

Integrate CRSF barometer detection into baro subsystem

src/main/sensors/barometer.c


12. src/main/sensors/barometer.h ✨ Enhancement +2/-1

Add BARO_CRSF enum and renumber BARO_FAKE

src/main/sensors/barometer.h


13. src/main/sensors/battery.c ✨ Enhancement +27/-0

Add CRSF voltage and current sensor integration

src/main/sensors/battery.c


14. src/main/sensors/battery_config_structs.h ✨ Enhancement +4/-2

Add CRSF to voltage and current sensor enums

src/main/sensors/battery_config_structs.h


15. src/main/io/serial.h ✨ Enhancement +1/-1

Repurpose FUNCTION_UNUSED_2 as FUNCTION_CRSF_SENSOR

src/main/io/serial.h


16. src/main/fc/fc_init.c ✨ Enhancement +5/-0

Initialize CRSF sensor input during FC startup

src/main/fc/fc_init.c


17. src/main/fc/fc_tasks.c ✨ Enhancement +21/-0

Add TASK_CRSF_SENSOR scheduler task at 100 Hz

src/main/fc/fc_tasks.c


18. src/main/scheduler/scheduler.h ✨ Enhancement +3/-0

Add TASK_CRSF_SENSOR to task enumeration

src/main/scheduler/scheduler.h


19. src/main/telemetry/crsf.c ✨ Enhancement +12/-1

Use CRSF sensor vario data for outgoing telemetry

src/main/telemetry/crsf.c


20. src/main/target/common_post.h ⚙️ Configuration changes +12/-0

Gate CRSF sensor features on flash size and CRSF RX

src/main/target/common_post.h


21. src/main/fc/settings.yaml ⚙️ Configuration changes +4/-4

Add CRSF options to baro, GPS, voltage, current enums

src/main/fc/settings.yaml


22. src/main/CMakeLists.txt ⚙️ Configuration changes +7/-0

Add CRSF sensor source files to build system

src/main/CMakeLists.txt


Grey Divider

Qodo Logo

@qodo-code-review
Copy link
Contributor

qodo-code-review bot commented Mar 2, 2026

Code Review by Qodo

🐞 Bugs (3) 📘 Rule violations (2) 📎 Requirement gaps (0)

Grey Divider


Action required

1. crsfSensorFrame[1] not validated 📘 Rule violation ⛯ Reliability
Description
The ISR frame assembler uses the received frameLength byte to compute fullFrameLength without
validating a minimum/valid range, which can cause frame assembly to stall/drop indefinitely or read
an invalid CRC location. This violates the requirement to validate external message payload
shape/length before use.
Code

src/main/io/crsf_sensor.c[R265-276]

+    const int fullFrameLength = crsfSensorFramePosition < 3 ? 5 : crsfSensorFrame[1] + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH;
+
+    if (fullFrameLength > CRSF_FRAME_SIZE_MAX) {
+        crsfSensorFramePosition = 0;
+        return;
+    }
+
+    if (crsfSensorFramePosition < fullFrameLength) {
+        crsfSensorFrame[crsfSensorFramePosition++] = (uint8_t)c;
+        if (crsfSensorFramePosition >= fullFrameLength) {
+            crsfSensorFrameDone = true;
+            crsfSensorFramePosition = 0;
Evidence
PR Compliance ID 1 requires validating external message lengths before indexing/using them. The new
ISR logic derives fullFrameLength directly from crsfSensorFrame[1] (external input) and then
uses it to control indexing/completion, but only checks an upper bound (> CRSF_FRAME_SIZE_MAX) and
does not reject too-small/invalid lengths.

src/main/io/crsf_sensor.c[265-276]
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 CRSF sensor UART ISR computes `fullFrameLength` from `crsfSensorFrame[1]` (external input) without validating a minimum valid range (e.g., type+CRC and known frame length constraints). Invalid/too-small lengths can prevent frame completion and lead to incorrect indexing/CRC handling.

## Issue Context
Compliance requires validating message payload length/shape before reading/indexing. The ISR currently only checks `fullFrameLength &gt; CRSF_FRAME_SIZE_MAX`.

## Fix Focus Areas
- src/main/io/crsf_sensor.c[265-276]

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


2. crsfBaroDetect() uses real defaults 📘 Rule violation ✓ Correctness
Description
The CRSF barometer initializes pressure/temperature to plausible real values (101325, 2500)
while crsfBaroLastUpdateMs is 0, allowing early reads to look like valid measurements before any
CRSF data is received. This violates the requirement to use explicit sentinel values for "no data
yet" states.
Code

↗ src/main/drivers/barometer/barometer_crsf.c

+bool crsfBaroDetect(baroDev_t *baro)
Evidence
PR Compliance ID 2 requires explicit sentinels for missing/unavailable measurements. The new CRSF
baro driver sets plausible readings and returns them from crsfBaroCalculate() as long as the
timeout has not elapsed, even though no data was received (crsfBaroLastUpdateMs = 0).

src/main/drivers/barometer/barometer_crsf.c[58-75]
src/main/drivers/barometer/barometer_crsf.c[92-95]
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 CRSF barometer driver initializes pressure/temperature to plausible real values and can report them as valid before receiving any CRSF data. This can mislead downstream code into treating startup defaults as real measurements.

## Issue Context
Compliance requires explicit sentinel values for &quot;no data yet&quot;/invalid states. `crsfBaroLastUpdateMs` is set to `0` in detect, but `crsfBaroCalculate()` only invalidates after the timeout and otherwise returns the stored values.

## Fix Focus Areas
- src/main/drivers/barometer/barometer_crsf.c[58-75]
- src/main/drivers/barometer/barometer_crsf.c[92-95]

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


3. Baro enum breaks upgrades 🐞 Bug ✓ Correctness
Description
BARO_CRSF is inserted before BARO_FAKE, renumbering BARO_FAKE from 12->13, but the barometer
parameter group version is unchanged, so existing EEPROM configs can be misinterpreted after upgrade
(e.g., previously-stored BARO_FAKE value now selects BARO_CRSF).
Code

src/main/sensors/barometer.h[R37-39]

+    BARO_CRSF   = 12,
+    BARO_FAKE   = 13,
    BARO_MAX    = BARO_FAKE
Evidence
The baro enum now assigns BARO_CRSF=12 and BARO_FAKE=13, changing the numeric value for BARO_FAKE.
INAV loads parameter groups via raw memcpy when the PG version matches; since barometerConfig’s PG
version remains 5, older stored values will be copied as-is and reinterpreted under the new enum
numbering.

src/main/sensors/barometer.h[25-40]
src/main/sensors/barometer.c[60-68]
src/main/config/parameter_group.c[86-94]

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

### Issue description
`baroSensor_e` was renumbered (inserting `BARO_CRSF` before `BARO_FAKE`). Because barometer config is persisted as raw bytes and its PG version was not bumped, existing EEPROM configurations can be silently reinterpreted (e.g., old `BARO_FAKE` value becomes `BARO_CRSF`).

### Issue Context
INAV parameter groups are loaded via memcpy when PG version matches. Changing enum numeric values without a PG version bump (and/or migration) is backward-incompatible.

### Fix Focus Areas
- src/main/sensors/barometer.h[25-40]
- src/main/sensors/barometer.c[60-68]
- src/main/config/parameter_group.c[86-94]

### Suggested fix approaches
- Prefer: keep numeric compatibility by assigning `BARO_CRSF` a new unused numeric value (e.g., after `BARO_FAKE`) so existing values remain unchanged.
- Or: bump `PG_BAROMETER_CONFIG` version and add migration/reset logic (accepting that older configs will reset to defaults for this PG).

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


View more (2)
4. CRSF frame buffer race 🐞 Bug ⛯ Reliability
Description
CRSF sensor input uses a single global frame buffer written by the UART ISR and later parsed by a
100Hz scheduler task without copying/locking, so frames can be overwritten mid-dispatch and multiple
frames can collapse into one—causing CRC failures and dropped sensor updates.
Code

src/main/io/crsf_sensor.c[R251-318]

+static void crsfSensorDataReceive(uint16_t c, void *rxCallbackData)
+{
+    UNUSED(rxCallbackData);
+
+    const timeUs_t currentTimeUs = microsISR();
+
+    if (cmpTimeUs(currentTimeUs, crsfSensorFrameStartAtUs) > CRSF_SENSOR_TIME_NEEDED_PER_FRAME_US) {
+        crsfSensorFramePosition = 0;
+    }
+
+    if (crsfSensorFramePosition == 0) {
+        crsfSensorFrameStartAtUs = currentTimeUs;
+    }
+
+    const int fullFrameLength = crsfSensorFramePosition < 3 ? 5 : crsfSensorFrame[1] + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH;
+
+    if (fullFrameLength > CRSF_FRAME_SIZE_MAX) {
+        crsfSensorFramePosition = 0;
+        return;
+    }
+
+    if (crsfSensorFramePosition < fullFrameLength) {
+        crsfSensorFrame[crsfSensorFramePosition++] = (uint8_t)c;
+        if (crsfSensorFramePosition >= fullFrameLength) {
+            crsfSensorFrameDone = true;
+            crsfSensorFramePosition = 0;
+        }
+    }
+}
+
+void crsfSensorInputInit(void)
+{
+    const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_CRSF_SENSOR);
+    if (!portConfig) {
+        return;
+    }
+
+    crsfSensorPort = openSerialPort(portConfig->identifier,
+        FUNCTION_CRSF_SENSOR,
+        crsfSensorDataReceive,
+        NULL,
+        CRSF_SENSOR_BAUDRATE,
+        MODE_RX,
+        CRSF_SENSOR_PORT_OPTIONS
+    );
+
+    crsfSensorVario = 0;
+    crsfSensorVarioLastUpdateMs = 0;
+}
+
+bool crsfSensorVarioIsValid(void)
+{
+    return (crsfSensorVarioLastUpdateMs > 0) &&
+           ((millis() - crsfSensorVarioLastUpdateMs) < CRSF_SENSOR_VARIO_TIMEOUT_MS);
+}
+
+int16_t crsfSensorGetVario(void)
+{
+    return crsfSensorVario;
+}
+
+// Called from scheduler to process completed frames outside ISR context
+void crsfSensorProcess(void)
+{
+    if (crsfSensorFrameDone) {
+        crsfSensorFrameDone = false;
+        crsfSensorDispatchFrame();
+    }
Evidence
The ISR writes into crsfSensorFrame and sets crsfSensorFrameDone=true then immediately resets
position to 0, allowing the next frame to start overwriting the same buffer. The non-ISR task later
calls crsfSensorDispatchFrame() which reads the same buffer (including length and CRC) with no
synchronization. Additionally, CRSF can produce frames up to 150Hz while the processing task runs at
100Hz, increasing the chance that multiple completed frames arrive between task executions (only one
boolean ‘done’ is stored).

src/main/io/crsf_sensor.c[66-71]
src/main/io/crsf_sensor.c[251-278]
src/main/io/crsf_sensor.c[312-318]
src/main/fc/fc_tasks.c[637-643]
src/main/rx/crsf.c[44-46]

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

### Issue description
`crsf_sensor` assembles frames in an ISR into a single global buffer and parses them later in a 100Hz task. Because the ISR can start writing the next frame immediately after setting `frameDone`, the task can read a partially-overwritten buffer (length/CRC/payload), producing CRC failures and sensor dropouts. Also, multiple frames arriving between task ticks are collapsed (only one boolean flag).

### Issue Context
CRSF can send frames up to ~150Hz. The task is 100Hz and runs at IDLE priority.

### Fix Focus Areas
- src/main/io/crsf_sensor.c[66-71]
- src/main/io/crsf_sensor.c[251-278]
- src/main/io/crsf_sensor.c[312-318]
- src/main/fc/fc_tasks.c[637-643]

### Suggested fix approaches
- Implement double buffering: ISR fills buffer A; when complete, atomically swaps a pointer/index to buffer B for task consumption.
- Or implement a small ring buffer of fixed-size frames with head/tail indices updated atomically.
- Ensure `crsfSensorProcess()` drains all queued frames per call (while queue not empty) to reduce backlog.
- Consider raising task rate/priority if needed after correctness is ensured.

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


5. GPS altitude wraparound 🐞 Bug ✓ Correctness
Description
CRSF GPS altitude is encoded as uint16 meters with a +1000m offset, but decoding subtracts 1000
while still in unsigned arithmetic, so altitudes below 0m (altitude<1000) wrap to a huge positive
value and corrupt gpsSolDRV altitude.
Code

src/main/io/crsf_sensor.c[R109-117]

+    uint16_t groundSpeed = crsfSensorReadU16(payload + 8);   // km/h * 10
+    uint16_t heading = crsfSensorReadU16(payload + 10);      // degrees * 100
+    uint16_t altitude = crsfSensorReadU16(payload + 12);     // meters + 1000 offset
+    uint8_t numSat = payload[14];
+
+    gpsSolDRV.llh.lat = lat;    // degree / 10^7, same as INAV
+    gpsSolDRV.llh.lon = lon;
+    gpsSolDRV.llh.alt = (int32_t)(altitude - 1000) * 100;  // meters to cm
+    gpsSolDRV.groundSpeed = (groundSpeed * 100 + 18) / 36;  // km/h*10 to cm/s
Evidence
The CRSF GPS altitude field is uint16 with a -1000m offset. The new decode performs `altitude -
1000 while altitude is uint16_t`, so values <1000 underflow (e.g., 500-1000 wraps to 65036) and
then get cast to int32, producing an incorrect large altitude in cm.

src/main/telemetry/crsf.c[211-220]
src/main/io/crsf_sensor.c[109-117]

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

### Issue description
CRSF GPS altitude decoding underflows for altitudes below 0m because the subtraction is performed in `uint16_t` domain before casting.

### Issue Context
CRSF encodes altitude as `uint16` with a -1000m offset. Values &lt;1000 are valid and should decode to negative meters.

### Fix Focus Areas
- src/main/io/crsf_sensor.c[109-117]
- src/main/telemetry/crsf.c[211-220]

### Suggested fix
- Change to: `gpsSolDRV.llh.alt = ((int32_t)altitude - 1000) * 100;`
- (Optional) Add bounds checking if you want to guard against nonsense values from the external device.

ⓘ 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 +265 to +276
const int fullFrameLength = crsfSensorFramePosition < 3 ? 5 : crsfSensorFrame[1] + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH;

if (fullFrameLength > CRSF_FRAME_SIZE_MAX) {
crsfSensorFramePosition = 0;
return;
}

if (crsfSensorFramePosition < fullFrameLength) {
crsfSensorFrame[crsfSensorFramePosition++] = (uint8_t)c;
if (crsfSensorFramePosition >= fullFrameLength) {
crsfSensorFrameDone = true;
crsfSensorFramePosition = 0;
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. crsfsensorframe[1] not validated 📘 Rule violation ⛯ Reliability

The ISR frame assembler uses the received frameLength byte to compute fullFrameLength without
validating a minimum/valid range, which can cause frame assembly to stall/drop indefinitely or read
an invalid CRC location. This violates the requirement to validate external message payload
shape/length before use.
Agent Prompt
## Issue description
The CRSF sensor UART ISR computes `fullFrameLength` from `crsfSensorFrame[1]` (external input) without validating a minimum valid range (e.g., type+CRC and known frame length constraints). Invalid/too-small lengths can prevent frame completion and lead to incorrect indexing/CRC handling.

## Issue Context
Compliance requires validating message payload length/shape before reading/indexing. The ISR currently only checks `fullFrameLength > CRSF_FRAME_SIZE_MAX`.

## Fix Focus Areas
- src/main/io/crsf_sensor.c[265-276]

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

Comment on lines +37 to 39
BARO_CRSF = 12,
BARO_FAKE = 13,
BARO_MAX = BARO_FAKE
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. Baro enum breaks upgrades 🐞 Bug ✓ Correctness

BARO_CRSF is inserted before BARO_FAKE, renumbering BARO_FAKE from 12->13, but the barometer
parameter group version is unchanged, so existing EEPROM configs can be misinterpreted after upgrade
(e.g., previously-stored BARO_FAKE value now selects BARO_CRSF).
Agent Prompt
### Issue description
`baroSensor_e` was renumbered (inserting `BARO_CRSF` before `BARO_FAKE`). Because barometer config is persisted as raw bytes and its PG version was not bumped, existing EEPROM configurations can be silently reinterpreted (e.g., old `BARO_FAKE` value becomes `BARO_CRSF`).

### Issue Context
INAV parameter groups are loaded via memcpy when PG version matches. Changing enum numeric values without a PG version bump (and/or migration) is backward-incompatible.

### Fix Focus Areas
- src/main/sensors/barometer.h[25-40]
- src/main/sensors/barometer.c[60-68]
- src/main/config/parameter_group.c[86-94]

### Suggested fix approaches
- Prefer: keep numeric compatibility by assigning `BARO_CRSF` a new unused numeric value (e.g., after `BARO_FAKE`) so existing values remain unchanged.
- Or: bump `PG_BAROMETER_CONFIG` version and add migration/reset logic (accepting that older configs will reset to defaults for this PG).

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

Comment on lines +251 to +318
static void crsfSensorDataReceive(uint16_t c, void *rxCallbackData)
{
UNUSED(rxCallbackData);

const timeUs_t currentTimeUs = microsISR();

if (cmpTimeUs(currentTimeUs, crsfSensorFrameStartAtUs) > CRSF_SENSOR_TIME_NEEDED_PER_FRAME_US) {
crsfSensorFramePosition = 0;
}

if (crsfSensorFramePosition == 0) {
crsfSensorFrameStartAtUs = currentTimeUs;
}

const int fullFrameLength = crsfSensorFramePosition < 3 ? 5 : crsfSensorFrame[1] + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH;

if (fullFrameLength > CRSF_FRAME_SIZE_MAX) {
crsfSensorFramePosition = 0;
return;
}

if (crsfSensorFramePosition < fullFrameLength) {
crsfSensorFrame[crsfSensorFramePosition++] = (uint8_t)c;
if (crsfSensorFramePosition >= fullFrameLength) {
crsfSensorFrameDone = true;
crsfSensorFramePosition = 0;
}
}
}

void crsfSensorInputInit(void)
{
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_CRSF_SENSOR);
if (!portConfig) {
return;
}

crsfSensorPort = openSerialPort(portConfig->identifier,
FUNCTION_CRSF_SENSOR,
crsfSensorDataReceive,
NULL,
CRSF_SENSOR_BAUDRATE,
MODE_RX,
CRSF_SENSOR_PORT_OPTIONS
);

crsfSensorVario = 0;
crsfSensorVarioLastUpdateMs = 0;
}

bool crsfSensorVarioIsValid(void)
{
return (crsfSensorVarioLastUpdateMs > 0) &&
((millis() - crsfSensorVarioLastUpdateMs) < CRSF_SENSOR_VARIO_TIMEOUT_MS);
}

int16_t crsfSensorGetVario(void)
{
return crsfSensorVario;
}

// Called from scheduler to process completed frames outside ISR context
void crsfSensorProcess(void)
{
if (crsfSensorFrameDone) {
crsfSensorFrameDone = false;
crsfSensorDispatchFrame();
}
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. Crsf frame buffer race 🐞 Bug ⛯ Reliability

CRSF sensor input uses a single global frame buffer written by the UART ISR and later parsed by a
100Hz scheduler task without copying/locking, so frames can be overwritten mid-dispatch and multiple
frames can collapse into one—causing CRC failures and dropped sensor updates.
Agent Prompt
### Issue description
`crsf_sensor` assembles frames in an ISR into a single global buffer and parses them later in a 100Hz task. Because the ISR can start writing the next frame immediately after setting `frameDone`, the task can read a partially-overwritten buffer (length/CRC/payload), producing CRC failures and sensor dropouts. Also, multiple frames arriving between task ticks are collapsed (only one boolean flag).

### Issue Context
CRSF can send frames up to ~150Hz. The task is 100Hz and runs at IDLE priority.

### Fix Focus Areas
- src/main/io/crsf_sensor.c[66-71]
- src/main/io/crsf_sensor.c[251-278]
- src/main/io/crsf_sensor.c[312-318]
- src/main/fc/fc_tasks.c[637-643]

### Suggested fix approaches
- Implement double buffering: ISR fills buffer A; when complete, atomically swaps a pointer/index to buffer B for task consumption.
- Or implement a small ring buffer of fixed-size frames with head/tail indices updated atomically.
- Ensure `crsfSensorProcess()` drains all queued frames per call (while queue not empty) to reduce backlog.
- Consider raising task rate/priority if needed after correctness is ensured.

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

Comment on lines +109 to +117
uint16_t groundSpeed = crsfSensorReadU16(payload + 8); // km/h * 10
uint16_t heading = crsfSensorReadU16(payload + 10); // degrees * 100
uint16_t altitude = crsfSensorReadU16(payload + 12); // meters + 1000 offset
uint8_t numSat = payload[14];

gpsSolDRV.llh.lat = lat; // degree / 10^7, same as INAV
gpsSolDRV.llh.lon = lon;
gpsSolDRV.llh.alt = (int32_t)(altitude - 1000) * 100; // meters to cm
gpsSolDRV.groundSpeed = (groundSpeed * 100 + 18) / 36; // km/h*10 to cm/s
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

5. Gps altitude wraparound 🐞 Bug ✓ Correctness

CRSF GPS altitude is encoded as uint16 meters with a +1000m offset, but decoding subtracts 1000
while still in unsigned arithmetic, so altitudes below 0m (altitude<1000) wrap to a huge positive
value and corrupt gpsSolDRV altitude.
Agent Prompt
### Issue description
CRSF GPS altitude decoding underflows for altitudes below 0m because the subtraction is performed in `uint16_t` domain before casting.

### Issue Context
CRSF encodes altitude as `uint16` with a -1000m offset. Values <1000 are valid and should decode to negative meters.

### Fix Focus Areas
- src/main/io/crsf_sensor.c[109-117]
- src/main/telemetry/crsf.c[211-220]

### Suggested fix
- Change to: `gpsSolDRV.llh.alt = ((int32_t)altitude - 1000) * 100;`
- (Optional) Add bounds checking if you want to guard against nonsense values from the external device.

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

@sensei-hacker
Copy link
Member Author

according to my knowledge the Radiomaster Sensor Configuration LUA sends MSP-over-CRSF messages as we discussed earlier.

Can we verify that, as we discussed earlier? You mentioned a logic analyzer - that would certainly do the trick.

I don't want to spam the sensor with garbage it can't use 100 times per second by passing it all CRSF from the radio as originally requested. That would be needlessly taking time away from our PID loop and possibly making the sensor less reliable by sending it "random junk" that it doesn't understand. I'd prefer to send it only what it is set up to handle.

@wimalopaan
Copy link

wimalopaan commented Mar 2, 2026

according to my knowledge the Radiomaster Sensor Configuration LUA sends MSP-over-CRSF messages as we discussed earlier.

Can we verify that, as we discussed earlier? You mentioned a logic analyzer - that would certainly do the trick.

I don't want to spam the sensor with garbage it can't use 100 times per second by passing it all CRSF from the radio as originally requested. That would be needlessly taking time away from our PID loop and possibly making the sensor less reliable by sending it "random junk" that it doesn't understand. I'd prefer to send it only what it is set up to handle.

Sure. I'll be back with LA traces for these packages. For the beginning, I'll use the BATT sensor CU01

@Target0815
Copy link

Gated on MCU_FLASH_SIZE > 512 to exclude F722 and other flash-constrained targets

The sensors make sense on the RM NEXUS-X / -XR. Unfortunately, the firmware does not allow this to be tested on the target. I have an ERS-GPS available here.

@wimalopaan
Copy link

wimalopaan commented Mar 2, 2026

The following screenshots are for the three basic operations:

  1. Ping (is sent on start of LUA) -> ping respose
  2. Device select -> device select response
  3. Parameter write -> parameter write response

The LUA defines the following operations:

CRSF_FRAMETYPE_MSP_REQ = 0x7A
CRSF_FRAMETYPE_MSP_RESP = 0x7B
CRSF_FRAMETYPE_MSP_WRITE = 0x7C
CRSF_FRAME_CUSTOM_TELEM = 0x88

but I could only see 0x7c and 0x7b.

The LUA also uses the following fixed extended addresses (for all devices):

local CRSF_ADDRESS_BETAFLIGHT = 0xC8
local CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA

Clearly, the first sensor in the daisy-chain of sensors receives also all other packages like rc-channels and link-stats. But the sensors do not forward these packages, so from he second sensor on, no rc-channels and link-stat packages are seen.

If you need more, please let me know!
Hope that helps.

Ping:

ping

Ping response:

ping_resp

Device select:

device

Device select response:

device_resp

Parameter write:

write

Parameter write response:

write_resp

@sensei-hacker
Copy link
Member Author

sensei-hacker commented Mar 2, 2026

Gated on MCU_FLASH_SIZE > 512 to exclude F722 and other flash-constrained targets

The sensors make sense on the RM NEXUS-X / -XR. Unfortunately, the firmware does not allow this to be tested on the target. I have an ERS-GPS available here.

Yes unfortunately the F722 flash is full, and has been been for two years.
A couple years ago it filled up and we started having to remove features from the F722 and F411 to make room for any adding any new feature on F722.

@Target0815
Copy link

Yes unfortunately the F722 flash is full, and has been been for two years.

Yes, it's a shame, but I understand the problem. @wimalopaan was kind enough to provide a target that I could test with. With your change, the RM ERS-GPS is functional in any case.

Personally, I would prefer to use a normal GPS, but I could probably use a CU sensor. I can't think of anything right now that could be dispensed with. Maybe you could name two or three features that take up a lot of memory.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants