Full Code of dgatf/msrc for AI

master 95b865993dd2 cached
189 files
1.4 MB
370.9k tokens
643 symbols
1 requests
Download .txt
Showing preview only (1,474K chars total). Download the full file or copy to clipboard to get everything.
Repository: dgatf/msrc
Branch: master
Commit: 95b865993dd2
Files: 189
Total size: 1.4 MB

Directory structure:
gitextract_7zabuz1p/

├── .clang-format
├── .gitattributes
├── .github/
│   ├── copilot-instructions.md
│   └── workflows/
│       ├── build_release.yaml
│       ├── ci_firmware.yaml
│       ├── ci_msrc_link.yaml
│       ├── dev_firmware.yaml
│       └── dev_msrc_link.yaml
├── .gitignore
├── .gitmodules
├── .vscode/
│   ├── c_cpp_properties.json
│   ├── launch.json
│   └── settings.json
├── LICENSE
├── README.md
├── board/
│   ├── CMakeLists.txt
│   ├── freertos/
│   │   ├── CMakeLists.txt
│   │   └── FreeRTOSConfig.h
│   ├── pico_sdk_import.cmake
│   └── project/
│       ├── CMakeLists.txt
│       ├── common.c
│       ├── common.h
│       ├── config.c
│       ├── config.h
│       ├── constants.h
│       ├── dbg_rb.c
│       ├── dbg_rb.h
│       ├── dbg_task.c
│       ├── dbg_task.h
│       ├── led.c
│       ├── led.h
│       ├── main.c
│       ├── pio/
│       │   ├── CMakeLists.txt
│       │   ├── capture_edge.c
│       │   ├── capture_edge.h
│       │   ├── capture_edge.pio
│       │   ├── castle_link.c
│       │   ├── castle_link.h
│       │   ├── castle_link.pio
│       │   ├── i2c_multi.c
│       │   ├── i2c_multi.h
│       │   ├── i2c_multi.pio
│       │   ├── uart_rx.c
│       │   ├── uart_rx.h
│       │   ├── uart_rx.pio
│       │   ├── uart_tx.c
│       │   ├── uart_tx.h
│       │   ├── uart_tx.pio
│       │   ├── ws2812.c
│       │   ├── ws2812.h
│       │   └── ws2812.pio
│       ├── protocol/
│       │   ├── CMakeLists.txt
│       │   ├── crsf.c
│       │   ├── crsf.h
│       │   ├── fbus.c
│       │   ├── fbus.h
│       │   ├── fport.c
│       │   ├── fport.h
│       │   ├── frsky_d.c
│       │   ├── frsky_d.h
│       │   ├── ghst.c
│       │   ├── ghst.h
│       │   ├── hitec.c
│       │   ├── hitec.h
│       │   ├── hott.c
│       │   ├── hott.h
│       │   ├── ibus.c
│       │   ├── ibus.h
│       │   ├── jetiex.c
│       │   ├── jetiex.h
│       │   ├── jetiex_sensor.c
│       │   ├── jetiex_sensor.h
│       │   ├── jr_dmss.c
│       │   ├── jr_dmss.h
│       │   ├── multiplex.c
│       │   ├── multiplex.h
│       │   ├── sanwa.c
│       │   ├── sanwa.h
│       │   ├── sbus.c
│       │   ├── sbus.h
│       │   ├── smartport.c
│       │   ├── smartport.h
│       │   ├── srxl.c
│       │   ├── srxl.h
│       │   ├── srxl2.c
│       │   ├── srxl2.h
│       │   ├── xbus.c
│       │   └── xbus.h
│       ├── sensor/
│       │   ├── CMakeLists.txt
│       │   ├── airspeed.c
│       │   ├── airspeed.h
│       │   ├── auto_offset.c
│       │   ├── auto_offset.h
│       │   ├── bmp180.c
│       │   ├── bmp180.h
│       │   ├── bmp280.c
│       │   ├── bmp280.h
│       │   ├── cell_count.c
│       │   ├── cell_count.h
│       │   ├── current.c
│       │   ├── current.h
│       │   ├── distance.c
│       │   ├── distance.h
│       │   ├── esc_apd_f.c
│       │   ├── esc_apd_f.h
│       │   ├── esc_apd_hv.c
│       │   ├── esc_apd_hv.h
│       │   ├── esc_castle.c
│       │   ├── esc_castle.h
│       │   ├── esc_hw3.c
│       │   ├── esc_hw3.h
│       │   ├── esc_hw4.c
│       │   ├── esc_hw4.h
│       │   ├── esc_hw5.c
│       │   ├── esc_hw5.h
│       │   ├── esc_kontronik.c
│       │   ├── esc_kontronik.h
│       │   ├── esc_omp_m4.c
│       │   ├── esc_omp_m4.h
│       │   ├── esc_openyge.c
│       │   ├── esc_openyge.h
│       │   ├── esc_pwm.c
│       │   ├── esc_pwm.h
│       │   ├── esc_ztw.c
│       │   ├── esc_ztw.h
│       │   ├── fuel_meter.c
│       │   ├── fuel_meter.h
│       │   ├── gpio.c
│       │   ├── gpio.h
│       │   ├── gps.c
│       │   ├── gps.h
│       │   ├── ina3221.c
│       │   ├── ina3221.h
│       │   ├── mpu6050.c
│       │   ├── mpu6050.h
│       │   ├── ms5611.c
│       │   ├── ms5611.h
│       │   ├── ntc.c
│       │   ├── ntc.h
│       │   ├── pwm_out.c
│       │   ├── pwm_out.h
│       │   ├── smart_esc.c
│       │   ├── smart_esc.h
│       │   ├── voltage.c
│       │   ├── voltage.h
│       │   ├── vspeed.c
│       │   ├── vspeed.h
│       │   ├── xgzp68xxd.c
│       │   └── xgzp68xxd.h
│       ├── serial_monitor.c
│       ├── serial_monitor.h
│       ├── sim_rx.c
│       ├── sim_rx.h
│       ├── uart.c
│       ├── uart.h
│       ├── uart_pio.c
│       ├── uart_pio.h
│       ├── usb.c
│       └── usb.h
├── case/
│   ├── MSRC_case_zero-Lower case.stl
│   ├── MSRC_case_zero-Upper case.stl
│   ├── MSRC_case_zero.3mf
│   ├── MSRC_case_zero.FCStd
│   └── MSRC_case_zero_PLA_1h27m.gcode
├── include/
│   └── shared.h
├── lua/
│   └── MSRC.lua
├── msrc_gui/
│   ├── appdir/
│   │   └── msrc.desktop
│   ├── circuitdialog.cpp
│   ├── circuitdialog.h
│   ├── circuitdialog.ui
│   ├── main.cpp
│   ├── mainwindow.cpp
│   ├── mainwindow.h
│   ├── mainwindow.ui
│   ├── msrc_gui.pro
│   └── resources.qrc
└── msrc_gui_web/
    ├── README.md
    ├── css/
    │   └── style.css
    ├── index.html
    ├── js/
    │   ├── app.js
    │   ├── circuit.js
    │   ├── config_struct.js
    │   ├── serial.js
    │   ├── ui.js
    │   └── version.js
    ├── manifest.json
    ├── sw.js
    └── test/
        ├── layout_test.html
        └── verify_layout.js

================================================
FILE CONTENTS
================================================

================================================
FILE: .clang-format
================================================
BasedOnStyle: Google
IndentWidth: 4
ColumnLimit: 120

================================================
FILE: .gitattributes
================================================
case/** filter=lfs diff=lfs merge=lfs -text
case/** linguist-detectable=false


================================================
FILE: .github/copilot-instructions.md
================================================
# MSRC – Copilot Instructions

## Project Overview

MSRC (Multi Sensor for RC) is a telemetry system for RC models running on the **RP2040** microcontroller. It reads data from sensors (ESC, GPS, barometer, analog) and transmits it to an RC receiver using one of ~19 telemetry protocols. A companion **Qt5 desktop app** (`msrc_gui/`) configures the board over USB CDC. A Lua script (`lua/MSRC.lua`) enables wireless config from OpenTX/EdgeTX transmitters via SmartPort.

## Architecture

```
main.c  →  protocol_task (priority 3-4)  →  set_config()  →  sensor tasks (priority 2)
  ├── usb_task (priority 1)     GUI ↔ board binary protocol
  ├── led_task (priority 1)     WS2812 on GPIO 16
  └── dbg_task (priority 1)     Ring-buffer debug output
```

**Data flow:** Sensor tasks write to shared `float *` pointers (atomic on Cortex-M0+). Protocol tasks read these floats, format them per-protocol, and transmit to the receiver via UART/PIO. No mutexes are used for sensor data—relies on aligned 32-bit atomic writes.

**UART notification model:** ISRs push bytes into FreeRTOS queues, then after a packet-gap timeout call `vTaskNotifyGiveIndexedFromISR(context.uart0_notify_task_handle, 1, ...)`. Tasks block on `ulTaskNotifyTakeIndexed(1, pdTRUE, portMAX_DELAY)`.

## Key Directories

| Path | Purpose |
|------|---------|
| `board/project/protocol/` | 18 receiver protocol implementations (smartport, crsf, ibus, sbus, etc.) |
| `board/project/sensor/` | ~30 sensor drivers (ESC variants, GPS, baro, analog, fuel, GPIO) |
| `board/project/pio/` | PIO programs (.pio + .c/.h): soft UART, Castle Link, I2C, WS2812 |
| `board/project/` | Core firmware: main.c, config, UART, USB, LED, common utilities |
| `include/shared.h` | **Shared between firmware AND GUI** — all enums (`rx_protocol_t`, `esc_protocol_t`) and `config_t` struct |
| `msrc_gui/` | Qt5 desktop configuration app (MSRC Link) |
| `lua/MSRC.lua` | OpenTX/EdgeTX Lua script for wireless config via SmartPort |

## Protocol Communication Models

Protocols follow two models:

### Request/Response (SmartPort, IBUS, XBUS, Hitec, SBUS, SRXL, Multiplex, JetiEx, Sanwa, HOTT, JR DMSS)
The protocol task blocks on `ulTaskNotifyTakeIndexed(1, pdTRUE, portMAX_DELAY)` until the receiver sends a request. The task then parses the request, looks up the relevant sensor `float *` values, formats them per protocol, and sends a response.

### Periodic Push (CRSF, GHST, FBUS, FPort)
The protocol task sends telemetry frames at a fixed interval using `vTaskDelay()`, reading current sensor floats each cycle.

**SmartPort is special** — besides telemetry, it supports a maintenance/config mode for the Lua configuration script. Commands `0x30`/`0x31`/`0x32` get/set individual `config_t` fields by their SmartPort `data_id`.

## Adding a New Sensor

Follow the established pattern (see `board/project/sensor/esc_hw3.c` as reference):

1. **Header** — Define a parameter struct with config fields and `float *` output pointers:
   ```c
   typedef struct my_sensor_parameters_t {
       float alpha;
       float *value;  // allocated by protocol layer
   } my_sensor_parameters_t;
   ```
2. **Task function** — `void my_sensor_task(void *parameters)`:
   - Copy parameter struct locally: `my_sensor_parameters_t parameter = *(my_sensor_parameters_t *)parameters;`
   - Signal readiness: `xTaskNotifyGive(context.receiver_task_handle);`
   - Initialize output: `*parameter.value = 0;`
   - Loop: read hardware, apply `get_average()`, write to `*parameter.value`
3. **Wire in protocol** — In each protocol's `set_config()`, allocate `malloc(sizeof(float))` for the output pointer and create the sensor task with `xTaskCreate`. Wait for task init: `ulTaskNotifyTake(pdTRUE, portMAX_DELAY)`.
4. **CMake** — Add the `.c` file to `board/project/sensor/CMakeLists.txt`.
5. **Stack size** — Define `STACK_MY_SENSOR` in `constants.h` as `(measured_min + STACK_EXTRA)`.

## Adding a New Protocol

Follow the pattern in `board/project/protocol/ibus.c`:

1. **`set_config()`** — Read `config_t`, create sensor tasks based on enabled sensors, build protocol-specific sensor list.
2. **Main task** — Init UART via `uart0_begin()`, call `set_config()`, enter loop (request/response or periodic push).
3. **Format function** — Convert `float *` sensor values to protocol wire format (handle byte order, scaling, units).
4. **Register in `main.c`** — Add `case RX_MY_PROTO:` to the switch, calling `xTaskCreate(my_proto_task, ...)`.
5. **Update enums** — Add to `rx_protocol_t` in `include/shared.h` (**both** `#ifdef __cplusplus` and C blocks must be updated in sync).
6. **Update GUI** — Add the protocol to `msrc_gui/mainwindow.cpp` combo box (`ui->cbReceiver->addItem(...)`) and handle protocol-specific widget visibility in `on_cbReceiver_currentTextChanged()`.

## Spektrum Smart ESC/BAT Sensor

The Smart ESC driver (`board/project/sensor/smart_esc.c`) is the most complex sensor. It **emulates a Spektrum SRXL2 receiver** to communicate with a Spektrum Smart ESC/Battery over UART1 at 115200 baud.

### How it works
1. **PWM capture** — Uses PIO (`capture_edge`, pio0) to read throttle (GPIO 12) and reverse (GPIO 13) PWM signals from the actual receiver.
2. **SRXL2 handshake** — On startup, performs SRXL2 handshake with the ESC (ID `0x40`), presenting itself as receiver ID `0x21`.
3. **Control packets** — Every 10ms (`SRXL2_INTERVAL_MS`), sends `SRXL2_PACKET_TYPE_CONTROL` packets forwarding captured throttle/reverse channels. Requests telemetry every 10th packet (`reply_id = esc_id`).
4. **Telemetry parsing** — Receives telemetry in XBUS format, parsing two device types:
   - **`XBUS_ESC_ID`**: RPM, voltage, current, FET temp, BEC voltage/current, BEC temp
   - **`XBUS_SMART_BAT` (`0x42`)**: Sub-types `0x00` (realtime: temp, current, consumption), `0x10`/`0x20`/`0x30` (individual cell voltages, up to 18), `0x80` (battery ID: cell count, cycles)

### Parameter struct (extensive)
```c
typedef struct smart_esc_parameters_t {
    bool calc_consumption;
    float rpm_multiplier;
    float alpha_rpm, alpha_voltage, alpha_current, alpha_temperature;
    float *rpm, *voltage, *current, *temperature_fet, *temperature_bec, *voltage_bec, *current_bec;
    float *temperature_bat, *current_bat, *consumption;
    float *cell[18];
    uint8_t *cells;
    uint16_t *cycles;
} smart_esc_parameters_t;
```

### Protocol wiring
In `set_config()`, Smart ESC is created at **priority 4** (higher than normal sensors) because it needs low-latency SRXL2 timing. All 18 cell pointers are individually `malloc`'d. All protocols support Smart ESC — the wiring pattern in `set_config()` allocates ~25 float pointers:
```c
if (config->esc_protocol == ESC_SMART) {
    smart_esc_parameters_t parameter;
    parameter.rpm = malloc(sizeof(float));
    // ... allocate all pointers ...
    for (uint i = 0; i < 18; i++) parameter.cell[i] = malloc(sizeof(float));
    parameter.cells = malloc(sizeof(uint8_t));
    parameter.cycles = malloc(sizeof(uint16_t));
    xTaskCreate(smart_esc_task, "smart_esc_task", STACK_SMART_ESC, (void *)&parameter, 4, &task_handle);
    context.uart1_notify_task_handle = task_handle;
    ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
}
```

Config field: `config->smart_esc_calc_consumption` — if `true`, consumption is calculated from motor current via `get_consumption()` instead of using the Smart Battery's reported value.

## Config System

- `config_t` is defined in `include/shared.h` — shared across firmware, GUI, and Lua script.
- Stored in **RP2040 flash** at offset 768KB (`CONFIG_FLASH_TARGET_OFFSET`). Read via XIP pointer, written with interrupts disabled (`save_and_disable_interrupts()`).
- Supports migration from old flash offset (512KB → 768KB) in `config_read()`.
- Each field has a SmartPort `data_id` comment (0x5101–0x5152) used by the Lua config script.
- **When adding fields:** append before `spare` fields and decrement a spare. Bump `CONFIG_VERSION` in `config.h`. Update `config_forze_write()` defaults in `config.c`.
- Default values via compile-time `#define`s at top of `config.c` (e.g. `#define RX_PROTOCOL RX_SMARTPORT`).
- Defaults can be force-written holding GPIO 15 low at boot, or by `CONFIG_FORZE_WRITE`.

## USB Protocol (Board ↔ GUI)

Binary protocol over CDC USB serial. All messages start with header byte `0x30`:

| Bytes | Direction | Description |
|-------|-----------|-------------|
| `0x30 0x30` + `config_t` bytes | GUI→Board | Write config to flash (board blinks LED, writes, requires reset) |
| `0x30 0x31` | GUI→Board | Request current config |
| `0x30 0x32` + `config_t` bytes | Board→GUI | Config response |
| `0x30 0x33` | GUI→Board | Enable debug output (text stream over USB) |
| `0x30 0x34` | GUI→Board | Disable debug output |
| `0x30 0x35` | GUI→Board | Force write default config to flash |

The USB task (`board/project/usb.c`) polls every 1 second with `getchar_timeout_us(1000)`. Config is sent/received as raw `config_t` struct bytes — **both sides must agree on struct layout and `CONFIG_VERSION`**.

## GUI Application (MSRC Link)

Qt5/C++ desktop app in `msrc_gui/`. Key files:

| File | Purpose |
|------|---------|
| `mainwindow.cpp/.h` | Main application logic: serial comm, config UI, circuit diagram |
| `mainwindow.ui` | Qt Designer UI layout |
| `circuitdialog.cpp/.h` | Zoomable circuit diagram overlay dialog |
| `circuitdialog.ui` | Circuit dialog layout |
| `main.cpp` | App entry point |
| `msrc_gui.pro` | qmake project file |
| `res/` | PNG images for circuit diagram overlays (one per sensor/receiver type) |

### Architecture
- Uses `QSerialPort` at 115200/8N1 for USB CDC communication.
- Port list is auto-refreshed every 1 second via `QTimer`.
- On connect: disables debug, waits 2 seconds, requests config. Config arrives as `sizeof(config_t) + 2` bytes, validated by header `[0x30, 0x32]` and `config.version`.
- Two main flows: `setUiFromConfig()` (config struct → UI widgets) and `getConfigFromUi()` (UI widgets → config struct). These must be updated whenever `config_t` changes.
- **Circuit diagram**: `generateCircuit()` composites PNG overlays on a base RP2040 Zero pinout image depending on which sensors/receiver are enabled. Each sensor/receiver type has a dedicated PNG in `res/`.
- **Debug mode**: when enabled, all serial data is displayed as text in the debug panel (`ptDebug`).
- Config can be saved/loaded as `.cfg` binary files (raw `config_t` dump).
- Protocol-specific widgets are shown/hidden dynamically in `on_cbReceiver_currentTextChanged()` — e.g. fuel meter only for SmartPort/JetiEx/XBUS/HOTT/FPort/FBUS; GPIO only for SmartPort/FPort/FBUS.
- ESC combo maps directly to `esc_protocol_t` enum values (index + 1, since ESC_NONE = 0 means unchecked).

### When modifying the GUI
1. Update both `setUiFromConfig()` and `getConfigFromUi()` — they are the bidirectional mapping between `config_t` and UI.
2. For new receiver protocols: add to `cbReceiver` combo with the enum value as `userData`, update visibility logic in `on_cbReceiver_currentTextChanged()`.
3. For new sensors: add UI widgets in `mainwindow.ui`, update circuit diagram with a new PNG overlay.

## GPIO Pinout

| GPIO | Function |
|------|----------|
| 0 | UART0 TX → receiver RX |
| 1 | UART0 RX ← receiver TX |
| 2 | I2C1 SDA (receiver, with pull-up) |
| 3 | I2C1 SCL (receiver, with pull-up) |
| 4 | PWM capture / Castle PWM / UART1 TX (unused) |
| 5 | UART1 RX ← ESC TX / Castle ESC / Serial monitor |
| 6 | PIO UART RX ← GPS TX |
| 7 | Clock stretch NPN switch (XBUS) |
| 8 | I2C0 SDA (vario/sensors) |
| 9 | I2C0 SCL (vario/sensors) |
| 10 | PWM out |
| 11 | Fuel meter PWM capture |
| 12 | Smart ESC throttle PWM capture |
| 13 | Smart ESC reverse PWM capture |
| 14 | PIO UART TX → GPS RX |
| 15 | Restore default config (pull low at boot) |
| 16 | WS2812 LED |
| 17–22 | Digital GPIO switches |
| 26 | ADC0 — Voltage |
| 27 | ADC1 — Current |
| 28 | ADC2 — NTC temperature |
| 29 | ADC3 — Airspeed |

Assignments are in `board/project/constants.h` — **do not reuse pins** without checking this table.

## Lua Configuration Script

`lua/MSRC.lua` runs on OpenTX/EdgeTX transmitters for **wireless in-field configuration** via SmartPort telemetry. It reads/writes individual `config_t` fields by their `data_id` (0x5101–0x5152) using SmartPort maintenance mode (`0x30`/`0x31` frame commands). Pages: sensor ID, refresh rates, averaging, ESC config, GPS, vario, fuel meter, GPIO, analog sensors, gyro.

When adding a `config_t` field addressable via Lua: assign a `data_id` comment in `shared.h`, handle it in SmartPort maintenance mode (`smartport.c`), and add the corresponding entry in `MSRC.lua`.

## Build

```sh
# Firmware (requires Pico SDK, ARM toolchain)
cd board && mkdir build && cd build
cmake .. && make -j$(nproc)
# Output: MSRC-RP2040.uf2

# GUI (requires Qt5, including QtSerialPort)
cd msrc_gui && qmake && make
```

Version is derived from `git describe --tags`. The version string is injected as `PROJECT_VERSION` define in both firmware and GUI.

### Debugging with SWD probe
In `constants.h`, there are commented-out lines to remap UART from uart0 to uart1 for probe debugging. In `board/project/CMakeLists.txt`, toggle `pico_enable_stdio_usb` / `pico_enable_stdio_uart` (1/0 ↔ 0/1).

### Flashing
Hold BOOTSEL on the RP2040, connect USB, drag `MSRC-RP2040.uf2` to the mass storage device. Or use `picotool`.

## Code Conventions

- **C99** for firmware, **C++/Qt5** for GUI. No C++ in firmware code.
- Global `context_t context` in `main.c` holds all FreeRTOS task/queue handles—never create additional globals for IPC.
- Sensor averaging uses `get_average(alpha, prev, new)` (exponential moving average) from `common.c`. Alpha is stored in config as `float`, converted from user-facing "averaging elements" via `ALPHA(n) = 2.0 / (n + 1)`.
- Debug output via `debug(...)` macro—guarded by runtime `context.debug` flag, not compile-time. Can be toggled via USB commands.
- Timeout callbacks use `add_alarm_in_ms()` to zero sensor values on data loss.
- `#ifdef SIM_SENSORS` / `#ifdef SIM_RX` inject fake data for testing without hardware.
- PIO `.pio` files are compiled to headers via `pico_generate_pio_header()` in CMake.
- Byte order: use `swap_16()` / `swap_32()` macros from `common.h` for protocol wire formats.
- All structs used for wire protocols use `__attribute__((packed))`.

## FreeRTOS Priorities

| Priority | Tasks |
|----------|-------|
| 4 | SmartPort, FPort, FBUS, Smart ESC (latency-sensitive) |
| 3 | All other protocol tasks, timer service |
| 2 | All sensor tasks |
| 1 | USB, LED, debug |

Time slicing is **disabled** (`configUSE_TIME_SLICING 0`). Equal-priority tasks do not round-robin — each must yield explicitly. FreeRTOS tick rate is 500Hz (2ms). Task notification index 1 is used for UART data arrival (`configTASK_NOTIFICATION_ARRAY_ENTRIES = 3`).


================================================
FILE: .github/workflows/build_release.yaml
================================================
name: Build Release

on:
  release:
    types: [published]

env:
  FIRMWARE_FILENAME: MSRC-RP2040_${{ github.ref_name }}.uf2
  LINK_FILENAME: msrc_link_${{ github.ref_name }}

permissions:
  contents: write
  pages: write
  id-token: write
  
jobs:
  firmware:
    runs-on: ubuntu-latest

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        with:
          submodules: 'true'

      - name: Git tags
        run: git fetch --prune --unshallow

      - name: Build firmware
        uses: samyarsadat/Pico-Build-Action@v1
        with:
          source_dir: "board"
          output_dir: "../build"
          cmake_args: "-DCMAKE_BUILD_TYPE=Release"
      
      - name: Set version
        run: sudo mv build/project/MSRC-RP2040.uf2 build/project/MSRC-RP2040_${{ github.ref_name }}.uf2

      - name: Release
        uses: softprops/action-gh-release@v2
        with:
          files: build/project/MSRC-RP2040_${{ github.ref_name }}.uf2
            
      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/project/MSRC-RP2040_${{ github.ref_name }}.uf2
          github-token: ${{ secrets.TOKEN }}
        
  linux:
    runs-on: ubuntu-22.04

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: Install QT
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport

      
      - name: Git tags
        run: git fetch --prune --unshallow

      - name: Build
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          
      - name: Install LinuxDeploy
        run: |
          cd msrc_gui
          wget https://github.com/probonopd/linuxdeployqt/releases/download/continuous/linuxdeployqt-continuous-x86_64.AppImage
          sudo chmod +x linuxdeployqt-continuous-x86_64.AppImage
      
      - name: Install fuse
        run: sudo apt install libfuse2

      - name: Create AppImage
        run: |
          cp build/msrc_gui msrc_gui/appdir
          cd msrc_gui/appdir
          ../linuxdeployqt-continuous-x86_64.AppImage msrc.desktop -appimage -extra-plugins=iconengines,platformthemes/libqgtk3.so
          mv *.AppImage msrc_link_${{ github.ref_name }}.AppImage

      - name: Release
        uses: softprops/action-gh-release@v2
        with:
          files: msrc_gui/appdir/msrc_link_${{ github.ref_name }}.AppImage
              
      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: msrc_gui/appdir/msrc_link_${{ github.ref_name }}.AppImage
          github-token: ${{ secrets.TOKEN }}
            
  macos:
    runs-on: macos-14

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: Install QT
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport
        
      - name: Git tags
        run: git fetch --prune --unshallow

      - name: Build
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          mv msrc_gui.app msrc_link_${{ github.ref_name }}.app
          macdeployqt msrc_link_${{ github.ref_name }}.app -dmg
        
      - name: Release
        uses: softprops/action-gh-release@v2
        with:
          files: build/msrc_link_${{ github.ref_name }}.dmg
                
      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/msrc_link_${{ github.ref_name }}.dmg
          github-token: ${{ secrets.TOKEN }}

  windows:
    runs-on: windows-2022

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: Install qt static
        uses: orestonce/install-qt-static@v0.4.3
        with:
          version: Qt6.5.3-Windows-x86_64-MinGW13.2.0-ucrt-staticFull-20240527

      - name: Git tags
        run: git fetch --prune --unshallow
        
      - name: Build  
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          mingw32-make release
          mv release/msrc_gui.exe release/msrc_link_${{ github.ref_name }}.exe

      - name: Release
        uses: softprops/action-gh-release@v2
        with:
          files: build/release/msrc_link_${{ github.ref_name }}.exe
          
      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/release/msrc_link_${{ github.ref_name }}.exe
          github-token: ${{ secrets.TOKEN }}



================================================
FILE: .github/workflows/ci_firmware.yaml
================================================
# gh search commits --hash 272effd --repo dgatf/msrc

name: CI - MSRC firmware

on:
  workflow_dispatch: {}

jobs:
  build:
    runs-on: ubuntu-latest
    permissions:
        contents: read
        id-token: write 
        attestations: write

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        with:
          submodules: 'true'

      - name: Git tags
        run: git fetch --prune --unshallow

      - name: Build firmware
        uses: samyarsadat/Pico-Build-Action@v1
        with:
          source_dir: "board"
          output_dir: "../build"
          cmake_args: "-DCMAKE_BUILD_TYPE=Release"
        
      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/project/MSRC-RP2040.uf2
          github-token: ${{ secrets.TOKEN }}

      #- name: Upload artifact
      #  uses: actions/upload-artifact@v4
      #  with:
      #    overwrite: 'true'
      #    name: MSRC-RP2040.uf2
      #    path: build/project/MSRC-RP2040.uf2]]

      - name: Upload to Google Drive
        uses: logickoder/g-drive-upload@main
        with:
          credentials: ${{ secrets.GOOGLE_ID }}
          filename: 'build/project/MSRC-RP2040.uf2'
          folderId: ${{ secrets.FOLDER_ID }}
          overwrite: 'true'
          name: MSRC-RP2040.uf2


================================================
FILE: .github/workflows/ci_msrc_link.yaml
================================================
name: CI - MSRC Link

on:
  workflow_dispatch: {}

jobs:
  linux:
    runs-on: ubuntu-22.04
    permissions:
        contents: read
        id-token: write 
        attestations: write

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: Install QT
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport

      - name: Git tags
        run: git fetch --prune --unshallow

      - name: Build
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          
      - name: Install LinuxDeploy
        run: |
          cd msrc_gui
          wget https://github.com/probonopd/linuxdeployqt/releases/download/continuous/linuxdeployqt-continuous-x86_64.AppImage
          sudo chmod +x linuxdeployqt-continuous-x86_64.AppImage
      
      - name: Install fuse
        run: sudo apt install libfuse2

      - name: Create AppImage
        run: |
          cp build/msrc_gui msrc_gui/appdir
          cd msrc_gui/appdir
          ../linuxdeployqt-continuous-x86_64.AppImage msrc.desktop -appimage -extra-plugins=iconengines,platformthemes/libqgtk3.so
          mv *.AppImage msrc_gui.AppImage

      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: msrc_gui/appdir/msrc_gui.AppImage
          github-token: ${{ secrets.TOKEN }}

      - name: Upload to Google Drive
        uses: logickoder/g-drive-upload@main
        with:
          credentials: ${{ secrets.GOOGLE_ID }}
          filename: 'msrc_gui/appdir/msrc_gui.AppImage'
          folderId: ${{ secrets.FOLDER_ID }}
          overwrite: 'true'
          name: msrc_link.AppImage

  macos:
    runs-on: macos-14
    permissions:
        contents: read
        id-token: write 
        attestations: write

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: Install QT
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport
        
      - name: Git tags
        run: git fetch --prune --unshallow
      
      - name: Build
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          macdeployqt msrc_gui.app -dmg

      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/msrc_gui.dmg
          github-token: ${{ secrets.TOKEN }}
        
      - name: Upload to Google Drive
        uses: logickoder/g-drive-upload@main
        with:
          credentials: ${{ secrets.GOOGLE_ID }}
          filename: 'build/msrc_gui.dmg'
          folderId: ${{ secrets.FOLDER_ID }}
          overwrite: 'true'
          name: msrc_link.dmg

  windows:
    runs-on: windows-2022
    permissions:
        contents: read
        id-token: write 
        attestations: write

    steps:
      - name: Get actions code
        uses: actions/checkout@v4
        
      - name: install qt static
        uses: orestonce/install-qt-static@v0.4.3
        with:
          version: Qt6.5.3-Windows-x86_64-MinGW13.2.0-ucrt-staticFull-20240527

      - name: Git tags
        run: git fetch --prune --unshallow
        
      - name: Build  
        run: |
          mkdir build
          cd build
          qmake ../msrc_gui
          make
          mingw32-make release

      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: build/release/msrc_gui.exe
          github-token: ${{ secrets.TOKEN }}

      - name: Upload to Google Drive
        uses: logickoder/g-drive-upload@main
        with:
          credentials: ${{ secrets.GOOGLE_ID }}
          filename: 'build/release/msrc_gui.exe'
          folderId: ${{ secrets.FOLDER_ID }}
          overwrite: 'true'
          name: msrc_link.exe

================================================
FILE: .github/workflows/dev_firmware.yaml
================================================
name: Dev Release (Firmware)

on:
  workflow_dispatch: {}
  push:
    branches:
      - master
    paths:
      - board/**

permissions:
  contents: write
  id-token: write
  attestations: write

concurrency:
  group: dev-release-firmware
  cancel-in-progress: true

jobs:
  publish:
    runs-on: ubuntu-latest

    steps:
      - name: Checkout
        uses: actions/checkout@v4
        with:
          submodules: true
          fetch-depth: 0

      - name: Build firmware
        uses: samyarsadat/Pico-Build-Action@v1
        with:
          source_dir: "board"
          output_dir: "../build"
          cmake_args: "-DCMAKE_BUILD_TYPE=Release"

      - name: Prepare artifact
        run: |
          mkdir -p dist
          cp build/project/MSRC-RP2040.uf2 dist/MSRC_firmware.uf2

      - name: Generate attestation
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: dist/MSRC_firmware.uf2
          github-token: ${{ secrets.GITHUB_TOKEN }}

      - name: Write release body
        run: |
          cat > release_body.md << EOF
          Development (auto)

          Firmware:
          - commit: "${{ github.event.head_commit.message }}"
          - commit-url: "https://github.com/${{ github.repository }}/commit/${{ github.sha }}"

          EOF

      - name: Publish firmware to Development release
        uses: ncipollo/release-action@v1
        with:
          tag: dev-latest
          name: Development (auto)
          prerelease: true
          allowUpdates: true
          commit: ${{ github.sha }}
          artifacts: dist/MSRC_firmware.uf2
          artifactContentType: application/octet-stream
          replacesArtifacts: true
          generateReleaseNotes: false
          bodyFile: release_body.md

================================================
FILE: .github/workflows/dev_msrc_link.yaml
================================================
name: Dev Release - MSRC Link

on:
  workflow_dispatch: {}
  push:
    branches:
      - master
    paths:
      - msrc_gui/**

permissions:
  contents: write
  id-token: write
  attestations: write

concurrency:
  group: dev-release-link
  cancel-in-progress: true

jobs:
  linux:
    runs-on: ubuntu-22.04

    steps:
      - name: Checkout
        uses: actions/checkout@v4
        with:
          fetch-depth: 0

      - name: Install Qt
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport

      - name: Fetch tags
        run: git fetch --force --tags

      - name: Build
        run: |
          mkdir -p build
          cd build
          qmake ../msrc_gui
          make

      - name: Install linuxdeployqt
        run: |
          cd msrc_gui
          wget -q https://github.com/probonopd/linuxdeployqt/releases/download/continuous/linuxdeployqt-continuous-x86_64.AppImage
          chmod +x linuxdeployqt-continuous-x86_64.AppImage

      - name: Install fuse
        run: sudo apt-get update && sudo apt-get install -y libfuse2

      - name: Create AppImage
        run: |
          cp build/msrc_gui msrc_gui/appdir
          cd msrc_gui/appdir
          ../linuxdeployqt-continuous-x86_64.AppImage msrc.desktop -appimage -extra-plugins=iconengines,platformthemes/libqgtk3.so
          mv ./*.AppImage ./MSRC_Link_Linux.AppImage

      - name: Collect artifact
        run: |
          mkdir -p dist
          cp msrc_gui/appdir/MSRC_Link_Linux.AppImage dist/MSRC_Link_Linux.AppImage

      - name: Upload artifact (Linux)
        uses: actions/upload-artifact@v4
        with:
          name: msrc-link-linux
          path: dist/MSRC_Link_Linux.AppImage
          if-no-files-found: error

  macos:
    runs-on: macos-14

    steps:
      - name: Checkout
        uses: actions/checkout@v4
        with:
          fetch-depth: 0

      - name: Install Qt
        uses: jurplel/install-qt-action@v4
        with:
          version: '6.8.*'
          modules: qtserialport

      - name: Fetch tags
        run: git fetch --force --tags

      - name: Build
        run: |
          mkdir -p build
          cd build
          qmake ../msrc_gui
          make
          macdeployqt msrc_gui.app -dmg

      - name: Collect artifact
        run: |
          mkdir -p dist
          cp build/msrc_gui.dmg dist/MSRC_Link_macOS.dmg

      - name: Upload artifact (macOS)
        uses: actions/upload-artifact@v4
        with:
          name: msrc-link-macos
          path: dist/MSRC_Link_macOS.dmg
          if-no-files-found: error

  windows:
    runs-on: windows-2022

    steps:
      - name: Checkout
        uses: actions/checkout@v4
        with:
          fetch-depth: 0

      - name: Install Qt (static)
        uses: orestonce/install-qt-static@v0.4.3
        with:
          version: Qt6.5.3-Windows-x86_64-MinGW13.2.0-ucrt-staticFull-20240527

      - name: Fetch tags
        run: git fetch --force --tags

      - name: Build
        shell: bash
        run: |
          mkdir -p build
          cd build
          qmake ../msrc_gui
          make
          mingw32-make release

      - name: Collect Windows executable
        shell: bash
        run: |
          mkdir -p dist
          cp build/release/msrc_gui.exe dist/MSRC_Link_Windows.exe

      - name: Upload artifact (Windows)
        uses: actions/upload-artifact@v4
        with:
          name: msrc-link-windows
          path: dist/MSRC_Link_Windows.exe
          if-no-files-found: error

  publish:
    runs-on: ubuntu-latest
    needs: [linux, macos, windows]

    steps:
      - name: Download artifacts
        uses: actions/download-artifact@v4
        with:
          path: dist

      - name: Normalize dist layout
        run: |
          set -euo pipefail
          find dist -type f -name "MSRC_Link_Linux.AppImage" -exec cp -f {} dist/ \;
          find dist -type f -name "MSRC_Link_macOS.dmg" -exec cp -f {} dist/ \;
          find dist -type f -name "MSRC_Link_Windows.exe" -exec cp -f {} dist/ \;

          test -f dist/MSRC_Link_Linux.AppImage
          test -f dist/MSRC_Link_macOS.dmg
          test -f dist/MSRC_Link_Windows.exe

      - name: Generate attestation (Linux)
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: dist/MSRC_Link_Linux.AppImage
          github-token: ${{ secrets.GITHUB_TOKEN }}

      - name: Generate attestation (macOS)
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: dist/MSRC_Link_macOS.dmg
          github-token: ${{ secrets.GITHUB_TOKEN }}

      - name: Generate attestation (Windows)
        uses: actions/attest-build-provenance@v3
        with:
          subject-path: dist/MSRC_Link_Windows.exe
          github-token: ${{ secrets.GITHUB_TOKEN }}

      - name: Write release body
        run: |
          cat > release_body.md << EOF
          Development (auto)

          MSRC Link:
          - commit: "${{ github.event.head_commit.message }}"
          - commit-url: "https://github.com/${{ github.repository }}/commit/${{ github.sha }}"

          EOF

      - name: Publish MSRC Link to Development release
        uses: ncipollo/release-action@v1
        with:
          tag: dev-latest
          name: Development (auto)
          prerelease: true
          allowUpdates: true
          commit: ${{ github.sha }}
          artifacts: dist/MSRC_Link_Linux.AppImage,dist/MSRC_Link_macOS.dmg,dist/MSRC_Link_Windows.exe
          replacesArtifacts: true
          generateReleaseNotes: false

================================================
FILE: .gitignore
================================================
misc
build/
build_*/
msrc_gui/msrc_gui.pro.user*

### macOS ###
.DS_Store


================================================
FILE: .gitmodules
================================================
[submodule "board/freertos/FreeRTOS-Kernel"]
	path = board/freertos/FreeRTOS-Kernel
	url = https://github.com/FreeRTOS/FreeRTOS-Kernel.git


================================================
FILE: .vscode/c_cpp_properties.json
================================================
{
    "configurations": [
        {
            "name": "Default",
            "includePath": [
                "${workspaceFolder}/board/project/**",
                "${workspaceFolder}/build/**",
                "${env:PICO_SDK_PATH}/src/**",
                "${workspaceFolder}/board/freertos/FreeRTOS-Kernel/include/",
                "${workspaceFolder}/board/freertos/FreeRTOS-Kernel/portable/ThirdParty/GCC/RP2040/include/**",
                "${workspaceFolder}/board/freertos/"
            ],
            "intelliSenseMode": "gcc-arm",
            "compilerPath": "/usr/bin/arm-none-eabi-gcc",
            "cStandard": "c17",
            "cppStandard": "c++14"
        }
    ],
    "version": 4
}

================================================
FILE: .vscode/launch.json
================================================
{
    "version": "0.2.0",
    "configurations": [
        {
            "name": "Pico Debug",
            "cwd": "${workspaceRoot}",
            "executable": "${command:cmake.launchTargetPath}",
            "request": "launch",
            "type": "cortex-debug",
            "servertype": "openocd",
            //"gdbPath" : "${env:HOME}/.platformio/packages/toolchain-gccarmnoneeabi/bin/arm-none-eabi-gdb",
            "gdbPath" : "${env:HOME}/src/gcc-arm-none-eabi-10/bin/arm-none-eabi-gdb",
            "device": "RP2040",
            "configFiles": [
                "interface/picoprobe.cfg",
                "target/rp2040.cfg"
            ],
            "svdFile": "${env:PICO_SDK_PATH}/src/rp2040/hardware_regs/rp2040.svd",
            "runToMain": true,
            // Work around for stopping at main on restart
            "postRestartCommands": [
                "break main",
                "continue"
            ],
            "searchDir": ["${env:HOME}/src/pico/openocd/tcl"],
            //"showDevDebugOutput": true,
        }
    ]
}


================================================
FILE: .vscode/settings.json
================================================
{
    // These settings tweaks to the cmake plugin will ensure
    // that you debug using cortex-debug instead of trying to launch
    // a Pico binary on the host
    "C_Cpp.autoAddFileAssociations" : false,
    "C_Cpp.default.configurationProvider": "ms-vscode.cmake-tools",
    "cmake.options.statusBarVisibility" : "visible",
    "cmake.buildBeforeRun": true,
    "cmake.sourceDirectory": "${workspaceFolder}/board",
    "cortex-debug.openocdPath": "${env:HOME}/src/pico/openocd/src/openocd",
    "cortex-debug.armToolchainPath": "${env:HOME}/.platformio/packages/toolchain-gccarmnoneeabi/bin",
    "cortex-debug.variableUseNaturalFormat": true,
}


================================================
FILE: LICENSE
================================================
GNU GENERAL PUBLIC LICENSE
	 Version 3, 29 June 2007

Copyright (C) 2007 Free Software Foundation, Inc. <https://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.

				Preamble

The GNU General Public License is a free, copyleft license for
software and other kinds of works.

The licenses for most software and other practical works are designed
to take away your freedom to share and change the works.  By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users.  We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors.  You can apply it to
your programs, too.

When we speak of free software, we are referring to freedom, not
price.  Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.

To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights.  Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.

For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received.  You must make sure that they, too, receive
or can get the source code.  And you must show them these terms so they
know their rights.

Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.

For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software.  For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.

Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so.  This is fundamentally incompatible with the aim of
protecting users' freedom to change the software.  The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable.  Therefore, we
have designed this version of the GPL to prohibit the practice for those
products.  If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.

Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary.  To prevent this, the GPL assures that
patents cannot be used to render the program non-free.

The precise terms and conditions for copying, distribution and
modification follow.

	 TERMS AND CONDITIONS

0. Definitions.

"This License" refers to version 3 of the GNU General Public License.

"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.

"The Program" refers to any copyrightable work licensed under this
License.  Each licensee is addressed as "you".  "Licensees" and
"recipients" may be individuals or organizations.

To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy.  The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.

A "covered work" means either the unmodified Program or a work based
on the Program.

To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy.  Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.

To "convey" a work means any kind of propagation that enables other
parties to make or receive copies.  Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.

An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License.  If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.

1. Source Code.

The "source code" for a work means the preferred form of the work
for making modifications to it.  "Object code" means any non-source
form of a work.

A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.

The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form.  A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.

The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities.  However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work.  For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.

The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.

The Corresponding Source for a work in source code form is that
same work.

2. Basic Permissions.

All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met.  This License explicitly affirms your unlimited
permission to run the unmodified Program.  The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work.  This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.

You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force.  You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright.  Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.

Conveying under any other circumstances is permitted solely under
the conditions stated below.  Sublicensing is not allowed; section 10
makes it unnecessary.

3. Protecting Users' Legal Rights From Anti-Circumvention Law.

No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.

When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.

4. Conveying Verbatim Copies.

You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.

You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.

5. Conveying Modified Source Versions.

You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:

a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.

b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7.  This requirement modifies the requirement in section 4 to
"keep intact all notices".

c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy.  This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged.  This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.

d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.

A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit.  Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.

6. Conveying Non-Source Forms.

You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:

a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.

b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.

c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source.  This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.

d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge.  You need not require recipients to copy the
Corresponding Source along with the object code.  If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source.  Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.

e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.

A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.

A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling.  In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage.  For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product.  A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.

"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source.  The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.

If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information.  But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).

The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed.  Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.

Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.

7. Additional Terms.

"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law.  If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.

When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it.  (Additional permissions may be written to require their own
removal in certain cases when you modify the work.)  You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.

Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:

a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or

b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or

c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or

d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or

e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or

f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.

All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10.  If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term.  If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.

If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.

Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.

8. Termination.

You may not propagate or modify a covered work except as expressly
provided under this License.  Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).

However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.

Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.

Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License.  If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.

9. Acceptance Not Required for Having Copies.

You are not required to accept this License in order to receive or
run a copy of the Program.  Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance.  However,
nothing other than this License grants you permission to propagate or
modify any covered work.  These actions infringe copyright if you do
not accept this License.  Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.

10. Automatic Licensing of Downstream Recipients.

Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License.  You are not responsible
for enforcing compliance by third parties with this License.

An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations.  If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.

You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License.  For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.

11. Patents.

A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based.  The
work thus licensed is called the contributor's "contributor version".

A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version.  For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.

Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.

In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement).  To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.

If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients.  "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.

If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.

A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License.  You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.

Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.

12. No Surrender of Others' Freedom.

If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License.  If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all.  For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.

13. Use with the GNU Affero General Public License.

Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work.  The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.

14. Revised Versions of this License.

The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time.  Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.

Each version is given a distinguishing version number.  If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation.  If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.

If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.

Later license versions may give you additional or different
permissions.  However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.

15. Disclaimer of Warranty.

THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW.  EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU.  SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.

16. Limitation of Liability.

IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.

17. Interpretation of Sections 15 and 16.

If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.

 END OF TERMS AND CONDITIONS

How to Apply These Terms to Your New Programs

If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.

To do so, attach the following notices to the program.  It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.

<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year>  <name of author>

This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.

This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
GNU General Public License for more details.

You should have received a copy of the GNU General Public License
along with this program.  If not, see <https://www.gnu.org/licenses/>.

Also add information on how to contact you by electronic and paper mail.

If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:

<program>  Copyright (C) <year>  <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.

The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License.  Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".

You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<https://www.gnu.org/licenses/>.

The GNU General Public License does not permit incorporating your program
into proprietary programs.  If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library.  If this is what you want to do, use the GNU Lesser General
Public License instead of this License.  But first, please read
<https://www.gnu.org/licenses/why-not-lgpl.html>.


================================================
FILE: README.md
================================================
# MSRC – Multi Sensor Telemetry for RC (RP2040)

[![Donate](https://img.shields.io/badge/Donate-PayPal-green.svg)](https://www.paypal.com/donate/?business=9GKNBVGHKXFGW&no_recurring=0&currency_code=USD)

**MSRC** is a lightweight, low-cost, and highly flexible telemetry system for RC models, based on the RP2040 microcontroller.

It allows you to collect data from multiple sensors and transmit it to your receiver using a wide range of telemetry protocols. MSRC is a DIY alternative to commercial solutions, offering significantly reduced weight and cost while maintaining high flexibility and expandability.

---

## Features

- Multi-sensor telemetry system based on RP2040
- Support for multiple receiver telemetry protocols
- Support for various ESC telemetry protocols
- Modular design (only use the sensors you need)
- Fully configurable via PC using MSRC Link
- Lightweight and cost-effective

---

## Supported Receiver Protocols

- FrSky SmartPort
- FrSky D
- FrSky FPort
- FrSky FBUS
- Spektrum XBUS
- Spektrum SRXL / SRXL2
- FlySky IBUS
- Futaba SBUS2
- Multiplex Sensor Bus (MSB)
- Jeti EX Bus
- Jeti EX Sensor
- Hitec
- CRSF
- Sanwa
- HoTT
- JR DMSS
- GHST

---

## Supported Sensors

### ESC Telemetry

- Hobbywing V3 / V4 / V5 / FlyFun
- Kontronik
- KISS (APD F, BLHeli32, Summit X)
- APD HV / UHV
- OMP M4
- ZTW
- Castle Link
- PWM / phase sensor ESCs
- Spektrum Smart ESC & Battery

### GPS

- Serial GPS (NMEA)

### Vario (I2C)

- BMP180
- BMP280
- MS5611

### Analog Sensors

- Voltage
- Temperature
- Current
- Airspeed (MPXV7002)

### Fuel

- Fuel flow meter (PWM pulses)
- Fuel tank pressure (XGZP68XXD)

### Other

- Up to 6 digital switches (GPIO)

---

## Getting Started

1. Download the latest firmware from the **Releases** section  
2. Flash the firmware to your RP2040 board  
3. Connect your sensors and receiver  
4. Configure the device using **MSRC Link**  
5. Check telemetry on your transmitter  

👉 For detailed instructions, see the [Wiki](https://github.com/dgatf/msrc/wiki)

---

## Documentation

Full documentation is available in the wiki:

👉 https://github.com/dgatf/msrc/wiki

---

## Support

- Report issues: https://github.com/dgatf/msrc/issues  
- Discussion forums:
  - https://www.rcgroups.com/forums/showthread.php?4088405-DIY-MSRC-Multi-sensor-telemetry-for-several-Rx-protocols#post48830585  
  - https://www.helifreak.com/showthread.php?t=908371  
  - https://www.openrcforums.com/forum/viewtopic.php?f=84&t=11911  

If you would like to add support for a new receiver protocol or sensor, feel free to open an issue.

---

## Donate

If you find this project useful, consider supporting its development:

👉 https://www.paypal.com/donate/?business=9GKNBVGHKXFGW&no_recurring=0&currency_code=USD


================================================
FILE: board/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 3.17.0)

include(pico_sdk_import.cmake)

project(MSRC-RP2040)

include_directories(../include)

execute_process(
    COMMAND git config --global --add safe.directory /github/workspace
    COMMAND git describe --tags
    OUTPUT_VARIABLE PROJECT_VERSION
    OUTPUT_STRIP_TRAILING_WHITESPACE
)
message(STATUS "MSRC ${PROJECT_VERSION}") 
add_compile_definitions(PROJECT_VERSION="${PROJECT_VERSION}")

pico_sdk_init()

add_subdirectory(freertos)
add_subdirectory(project)


================================================
FILE: board/freertos/CMakeLists.txt
================================================
set(PICO_SDK_FREERTOS_SOURCE FreeRTOS-Kernel)

add_library(freertos
    ${PICO_SDK_FREERTOS_SOURCE}/event_groups.c
    ${PICO_SDK_FREERTOS_SOURCE}/list.c
    ${PICO_SDK_FREERTOS_SOURCE}/queue.c
    ${PICO_SDK_FREERTOS_SOURCE}/stream_buffer.c
    ${PICO_SDK_FREERTOS_SOURCE}/tasks.c
    ${PICO_SDK_FREERTOS_SOURCE}/timers.c
    ${PICO_SDK_FREERTOS_SOURCE}/portable/MemMang/heap_3.c
    ${PICO_SDK_FREERTOS_SOURCE}/portable/GCC/ARM_CM0/port.c
)

target_include_directories(freertos PUBLIC
    .
    ${PICO_SDK_FREERTOS_SOURCE}/include
    ${PICO_SDK_FREERTOS_SOURCE}/portable/GCC/ARM_CM0
)


================================================
FILE: board/freertos/FreeRTOSConfig.h
================================================
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H

/* Use Pico SDK ISR handlers */
#define vPortSVCHandler         isr_svcall
#define xPortPendSVHandler      isr_pendsv
#define xPortSysTickHandler     isr_systick

#define configUSE_PREEMPTION                    1
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
#define configUSE_TICKLESS_IDLE                 0
#define configCPU_CLOCK_HZ                      133000000
#define configTICK_RATE_HZ                      500
#define configMAX_PRIORITIES                    5
#define configMINIMAL_STACK_SIZE                128
#define configMAX_TASK_NAME_LEN                 16
#define configUSE_16_BIT_TICKS                  0
#define configIDLE_SHOULD_YIELD                 1
#define configUSE_TASK_NOTIFICATIONS            1
#define configTASK_NOTIFICATION_ARRAY_ENTRIES   3
#define configUSE_MUTEXES                       1
#define configUSE_RECURSIVE_MUTEXES             0
#define configUSE_COUNTING_SEMAPHORES           0
#define configQUEUE_REGISTRY_SIZE               10
#define configUSE_QUEUE_SETS                    0
#define configUSE_TIME_SLICING                  0
#define configUSE_NEWLIB_REENTRANT              0
#define configENABLE_BACKWARD_COMPATIBILITY     0
#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 5
#define configSTACK_DEPTH_TYPE                  uint16_t
#define configMESSAGE_BUFFER_LENGTH_TYPE        size_t

/* Memory allocation related definitions. */
#define configSUPPORT_STATIC_ALLOCATION         0
#define configSUPPORT_DYNAMIC_ALLOCATION        1
#define configAPPLICATION_ALLOCATED_HEAP        1

/* Hook function related definitions. */
#define configUSE_IDLE_HOOK                     0
#define configUSE_TICK_HOOK                     0
#define configCHECK_FOR_STACK_OVERFLOW          0
#define configUSE_MALLOC_FAILED_HOOK            0
#define configUSE_DAEMON_TASK_STARTUP_HOOK      0

/* Run time and task stats gathering related definitions. */
#define configGENERATE_RUN_TIME_STATS           0
#define configUSE_TRACE_FACILITY                0
#define configUSE_STATS_FORMATTING_FUNCTIONS    0

/* Co-routine related definitions. */
#define configUSE_CO_ROUTINES                   0
#define configMAX_CO_ROUTINE_PRIORITIES         1

/* Software timer related definitions. */
#define configUSE_TIMERS                        1
#define configTIMER_TASK_PRIORITY               3
#define configTIMER_QUEUE_LENGTH                10
#define configTIMER_TASK_STACK_DEPTH            configMINIMAL_STACK_SIZE

/* Define to trap errors during development. */
#define configASSERT( x )

/* Optional functions - most linkers will remove unused functions anyway. */
#define INCLUDE_vTaskPrioritySet                1
#define INCLUDE_uxTaskPriorityGet               1
#define INCLUDE_vTaskDelete                     1
#define INCLUDE_vTaskSuspend                    1
#define INCLUDE_xResumeFromISR                  1
#define INCLUDE_vTaskDelayUntil                 1
#define INCLUDE_vTaskDelay                      1
#define INCLUDE_xTaskGetSchedulerState          1
#define INCLUDE_xTaskGetCurrentTaskHandle       1
#define INCLUDE_uxTaskGetStackHighWaterMark     1
#define INCLUDE_xTaskGetIdleTaskHandle          0
#define INCLUDE_eTaskGetState                   0
#define INCLUDE_xEventGroupSetBitFromISR        1
#define INCLUDE_xTimerPendFunctionCall          0
#define INCLUDE_xTaskAbortDelay                 0
#define INCLUDE_xTaskGetHandle                  0
#define INCLUDE_xTaskResumeFromISR              1

/* A header file that defines trace macro can be included here. */

#endif /* FREERTOS_CONFIG_H */


================================================
FILE: board/pico_sdk_import.cmake
================================================
# This is a copy of <PICO_SDK_PATH>/external/pico_sdk_import.cmake

# This can be dropped into an external project to help locate this SDK
# It should be include()ed prior to project()

# todo document

if (DEFINED ENV{PICO_SDK_PATH} AND (NOT PICO_SDK_PATH))
    set(PICO_SDK_PATH $ENV{PICO_SDK_PATH})
    message("Using PICO_SDK_PATH from environment ('${PICO_SDK_PATH}')")
endif ()

if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT} AND (NOT PICO_SDK_FETCH_FROM_GIT))
    set(PICO_SDK_FETCH_FROM_GIT $ENV{PICO_SDK_FETCH_FROM_GIT})
    message("Using PICO_SDK_FETCH_FROM_GIT from environment ('${PICO_SDK_FETCH_FROM_GIT}')")
endif ()

if (DEFINED ENV{PICO_SDK_FETCH_FROM_GIT_PATH} AND (NOT PICO_SDK_FETCH_FROM_GIT_PATH))
    set(PICO_SDK_FETCH_FROM_GIT_PATH $ENV{PICO_SDK_FETCH_FROM_GIT_PATH})
    message("Using PICO_SDK_FETCH_FROM_GIT_PATH from environment ('${PICO_SDK_FETCH_FROM_GIT_PATH}')")
endif ()

set(PICO_SDK_PATH "${PICO_SDK_PATH}" CACHE PATH "Path to the PICO SDK")
set(PICO_SDK_FETCH_FROM_GIT "${PICO_SDK_FETCH_FROM_GIT}" CACHE BOOL "Set to ON to fetch copy of PICO SDK from git if not otherwise locatable")
set(PICO_SDK_FETCH_FROM_GIT_PATH "${PICO_SDK_FETCH_FROM_GIT_PATH}" CACHE FILEPATH "location to download SDK")

if (NOT PICO_SDK_PATH)
    if (PICO_SDK_FETCH_FROM_GIT)
        include(FetchContent)
        set(FETCHCONTENT_BASE_DIR_SAVE ${FETCHCONTENT_BASE_DIR})
        if (PICO_SDK_FETCH_FROM_GIT_PATH)
            get_filename_component(FETCHCONTENT_BASE_DIR "${PICO_SDK_FETCH_FROM_GIT_PATH}" REALPATH BASE_DIR "${CMAKE_SOURCE_DIR}")
        endif ()
        FetchContent_Declare(
                pico_sdk
                GIT_REPOSITORY https://github.com/raspberrypi/pico-sdk
                GIT_TAG master
        )
        if (NOT pico_sdk)
            message("Downloading PICO SDK")
            FetchContent_Populate(pico_sdk)
            set(PICO_SDK_PATH ${pico_sdk_SOURCE_DIR})
        endif ()
        set(FETCHCONTENT_BASE_DIR ${FETCHCONTENT_BASE_DIR_SAVE})
    else ()
        message(FATAL_ERROR
                "PICO SDK location was not specified. Please set PICO_SDK_PATH or set PICO_SDK_FETCH_FROM_GIT to on to fetch from git."
                )
    endif ()
endif ()

get_filename_component(PICO_SDK_PATH "${PICO_SDK_PATH}" REALPATH BASE_DIR "${CMAKE_BINARY_DIR}")
if (NOT EXISTS ${PICO_SDK_PATH})
    message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' not found")
endif ()

set(PICO_SDK_INIT_CMAKE_FILE ${PICO_SDK_PATH}/pico_sdk_init.cmake)
if (NOT EXISTS ${PICO_SDK_INIT_CMAKE_FILE})
    message(FATAL_ERROR "Directory '${PICO_SDK_PATH}' does not appear to contain the PICO SDK")
endif ()

set(PICO_SDK_PATH ${PICO_SDK_PATH} CACHE PATH "Path to the PICO SDK" FORCE)

include(${PICO_SDK_INIT_CMAKE_FILE})


================================================
FILE: board/project/CMakeLists.txt
================================================
include_directories(. pio protocol sensor)

add_executable(${PROJECT_NAME})

add_subdirectory(protocol)
add_subdirectory(sensor)
add_subdirectory(pio)

target_sources(${PROJECT_NAME} PRIVATE
    main.c
    uart.c
    common.c
    led.c
    config.c
    sim_rx.c
    uart_pio.c
    usb.c
    serial_monitor.c
    dbg_rb.c
    dbg_task.c
)

target_link_libraries(${PROJECT_NAME}
    pico_stdlib
    freertos
    hardware_uart
    hardware_irq
    hardware_pwm
    hardware_clocks
    hardware_adc
    hardware_pio
    hardware_i2c
    hardware_flash
    pico_i2c_slave
)

pico_add_extra_outputs(${PROJECT_NAME})

pico_enable_stdio_usb(${PROJECT_NAME} 1) # 1 normal, 0 probe debug 
pico_enable_stdio_uart(${PROJECT_NAME} 0) # 0 normal, 1 probe debug


================================================
FILE: board/project/common.c
================================================

#include "common.h"

#include <math.h>
#include <stdlib.h>

#include "hardware/adc.h"
#include "hardware/i2c.h"
#include "pico/stdlib.h"

float get_average(float alpha, float prev_value, float new_value) {
    if (isnan(new_value)) return prev_value;
    if (alpha > 1)
        return new_value;
    else
        return (1 - alpha) * prev_value + alpha * new_value;
}

float get_consumption(float current, uint16_t current_max, uint32_t *timestamp) {
    if (!*timestamp) {
        *timestamp = time_us_32();
        return 0;
    }
    uint32_t now = time_us_32();                    // us
    uint32_t interval = (now - *timestamp) / 1000;  // ms
    float mah = current * interval / 3600.0;
    *timestamp = now;
    if (interval > 2000 || (current_max && (mah > current_max * interval / 3600.0))) return 0;
    return mah;
}

float voltage_read(uint8_t adc_num) {
    adc_select_input(adc_num);
    return adc_read() * BOARD_VCC / ADC_RESOLUTION;
}

float get_altitude(float pressure, float temperature, float pressure_initial) {
    if (pressure_initial == 0) return 0;
    return (temperature + 273.15) * (1 - pow(pressure / pressure_initial, 1 / 5.256)) / 0.0065;
}

void get_vspeed(float *vspeed, float altitude, uint interval) {
    static float altitude_prev = 0;
    static uint ts = 0;
    uint now = time_us_32();
    if (now - ts >= interval * 1000) {
        *vspeed = (altitude - altitude_prev) / ((now - ts) / 1000000.0);
        altitude_prev = altitude;
        ts = time_us_32();
    }
}

void get_vspeed_gps(float *vspeed, float altitude, uint interval) {
    static float altitude_prev = 0;
    static uint ts = 0;
    uint now = time_us_32();
    if (now - ts >= interval * 1000) {
        *vspeed = (altitude - altitude_prev) / ((now - ts) / 1000000.0);
        altitude_prev = altitude;
        ts = time_us_32();
    }
}

/*
void circular_buffer_add(buffer_node_t *node, void *item)
{
    buffer_node_t *new_node = malloc(sizeof(buffer_node_t));
    new_node->item = item;
    if (node == NULL)
    {
        node = new_node;
        new_node->next = new_node;
    }
    else
    {
        new_node->next = node->next;
        node->next = new_node;
        node = new_node;
    }
}

void *circular_buffer_current()
{
    if (node)
        return node->item;
    return NULL;
}

void circular_buffer_next(buffer_node_t *node)
{
    if (node)
        node = node->next;
}

void circular_buffer_empty(buffer_node_t *node)
{
    if (node)
    {
        buffer_node_t *first_node, *next_node;
        first_node = node;
        do
        {
            next_node = node->next;
            free(node->item);
            free(node);
            node = next_node;
        } while (next_node != first_node);
        node = NULL;
    }
}
*/

================================================
FILE: board/project/common.h
================================================
#ifndef COMMON_H
#define COMMON_H

#include <FreeRTOS.h>
#include <queue.h>
#include <task.h>

#include "constants.h"
#include "pico/stdlib.h"
#include "pico/types.h"
#include "shared.h"
#include "dbg_task.h"

/*
   Debug
   Disconnect Vcc from the RC model to the board before connecting USB
   Telemetry may not work properly in debug mode
*/

#define MSRC_DEBUG 0  // 0 = no debug, 1 = debug level 1, 2 = debug level 2

// #define SIM_RX
// #define SIM_SENSORS

// #define SIM_SMARTPORT_SEND_CONFIG_LUA
// #define SIM_SMARTPORT_RECEIVE_CONFIG_LUA
// #define SIM_SMARTPORT_SEND_SENSOR_ID
// #define SIM_SMARTPORT_RECEIVE_SENSOR_ID

#define PI 3.14159265358979323846

#define swap_16(value) (((value & 0xFF) << 8) | (value & 0xFF00) >> 8)
#define swap_24(value) (((value & 0xFF) << 16) | (value & 0xFF00) | (value & 0xFF0000) >> 16)
#define swap_32(value) \
    (((value & 0xFF) << 24) | ((value & 0xFF00) << 8) | ((value & 0xFF0000) >> 8) | ((value & 0xFF000000) >> 24))

#define debug(...) \
    do { \
        if (context.debug) dbg_write(__VA_ARGS__); \
    } while (0)

#define debug_buffer(buffer, length, format) \
    do { \
        if (context.debug) \
            dbg_write_buffer((const uint8_t *)(buffer), (length), (format)); \
    } while (0)

#define debug2(...) \
    if (context.debug == 2) printf(__VA_ARGS__)
#define debug_buffer2(buffer, length, format) \
    if (context.debug == 2)                   \
        for (int i = 0; i < (length); i++) printf((format), (buffer)[i])

typedef struct context_t {
    TaskHandle_t pwm_out_task_handle, uart0_notify_task_handle, uart1_notify_task_handle, uart_pio_notify_task_handle,
        receiver_task_handle, led_task_handle, usb_task_handle;
    QueueHandle_t uart0_queue_handle, uart1_queue_handle, uart_rx_pio_queue_handle, uart_tx_pio_queue_handle, tasks_queue_handle,
        sensors_queue_handle;
    alarm_pool_t *uart_alarm_pool;
    uint8_t debug, led_cycles;
    uint16_t led_cycle_duration;
} context_t;

float get_average(float alpha, float prev_value, float new_value);
float get_consumption(float current, uint16_t current_max, uint32_t *timestamp);
float voltage_read(uint8_t adc_num);
float get_altitude(float pressure, float temperature, float P0);
void get_vspeed(float *vspeed, float altitude, uint interval);
void get_vspeed_gps(float *vspeed, float altitude, uint interval);

#endif

================================================
FILE: board/project/config.c
================================================
#include "config.h"

#include <hardware/flash.h>
#include <hardware/sync.h>
#include <stdio.h>
#include <string.h>

#include "pico/stdlib.h"

#define CONFIG_OLD_FLASH_TARGET_OFFSET (512 * 1024)  // 512kB after start of flash for program (uf2) + 512kB for config

/* Receiver protocol */
#define RX_PROTOCOL \
    RX_SMARTPORT  // RX_SMARTPORT, RX_XBUS, RX_SRXL, RX_FRSKY_D, RX_IBUS, RX_SBUS, RX_MULTIPLEX, RX_JETIEX, RX_HITEC
/* Sensors */
#define ESC_PROTOCOL ESC_NONE  // ESC_NONE, ESC_HW3, ESC_HW4, ESC_PWM, ESC_CASTLE, ESC_KONTRONIK, ESC_APD_F, ESC_APD_HV
#define ENABLE_GPS false
#define GPS_BAUD_RATE 9600
#define ENABLE_ANALOG_VOLTAGE false
#define ENABLE_ANALOG_CURRENT false
#define ENABLE_ANALOG_NTC false
#define ENABLE_ANALOG_AIRSPEED false
#define I2C1_TYPE I2C_NONE  // I2C_NONE, I2C_BMP280, I2C_MS5611, I2C_BMP180
#define I2C1_ADDRESS 0x77   // 0x76 (BMP280), 0x77 (BMP180, MS5611)
/* Pwm out */
#define ENABLE_PWM_OUT false
/* Refresh rate in ms (only Frsky) */
#define REFRESH_RATE_RPM 1000
#define REFRESH_RATE_VOLTAGE 1000
#define REFRESH_RATE_CURRENT 1000
#define REFRESH_RATE_TEMPERATURE 1000
#define REFRESH_RATE_GPS 1000
#define REFRESH_RATE_CONSUMPTION 1000
#define REFRESH_RATE_VARIO 1000
#define REFRESH_RATE_AIRSPEED 1000
#define REFRESH_RATE_DEFAULT 1000
/* Averaging elements (1 = no averaging) */
#define AVERAGING_ELEMENTS_RPM 1
#define AVERAGING_ELEMENTS_VOLTAGE 1
#define AVERAGING_ELEMENTS_CURRENT 1
#define AVERAGING_ELEMENTS_TEMPERATURE 1
#define AVERAGING_ELEMENTS_VARIO 1
#define AVERAGING_ELEMENTS_AIRSPEED 1

/* Analog rate*/
#define ANALOG_RATE 10
/* Analog voltage sensors */
#define ANALOG_VOLTAGE_MULTIPLIER 7.8  // 7.8 if using 68k and 10k as proposed in the docs
/* Analog current sensor */
#define ANALOG_CURRENT_MULTIPLIER 1  // current_multiplier = 1000 / sensitivity(mV/A)
/* Zero current output voltage offset or quiescent voltage (voltage offset when I = 0, Viout)
 - All hall effect core sensors (Amploc) are bidirectional. Viout=Vs/2
 - Hall effect coreless sensors (IC) (ACS758) can be bidirectional or directional. Recommended to use directional for
 higher sensitivity. Viout defined in datasheet
 - If CURRENT_AUTO_OFFSET is true, then after 5 seconds, voltage read is set as offset. It is recommended to use auto
 offset
*/
#define ANALOG_CURRENT_OFFSET 0
#define ANALOG_CURRENT_AUTO_OFFSET true
/* Analog airspeed */
#define AIRSPEED_OFFSET 0  // mV
#define AIRSPEED_VCC 5     // V

/* RPM multipliers (optional, this may be done in transmitter*/
#define RPM_PAIR_OF_POLES 1
#define RPM_PINION_TEETH 1  // For helis
#define RPM_MAIN_TEETH 1    // For helis

/* Vario */
#define VARIO_AUTO_OFFSET false
#define BMP280_FILTER 3  // BMP Filter. Higher filter = lower noise: 1 - low, 2 - medium, 3 - high

/* Only smartport and opentx */
#define SMARTPORT_SENSOR_ID 15    // Sensor Id
#define SMARTPORT_DATA_ID 0x5100  // DataId (sensor type)

/* Ibus */
#define IBUS_GPS_ALTERNATIVE_COORDINATES false

/* XBus */
#define XBUS_CLOCK_STRECH_SWITCH false
#define XBUS_ALTERNATIVE_VOLT_TEMP false

/* Jeti Ex */
#define JETI_GPS_SPEED_UNITS_KMH true

/* Serial monitor */
#define SERIAL_MONITOR_BAUDRATE 19200
#define SERIAL_MONITOR_STOPBITS 1
#define SERIAL_MONITOR_PARITY 0
#define SERIAL_MONITOR_TIMEOUT_MS 1
#define SERIAL_MONITOR_INVERTED false
#define SERIAL_MONITOR_GPIO 5    // GPIO 1 or 5
#define SERIAL_MONITOR_FORMAT 0  // 0 = hex, 1 = text

/* Add init delay for FlyFun ESC. Enable if the ESC doesn't arm */
#define ENABLE_ESC_INIT_DELAY false
#define ESC_INIT_DELAY_DURATION 10000

/* HW V4/V5 parameters */
#define ESC_HW4_MANUAL_OFFSET 1
#define ESC_HW4_CURRENT_OFFSET 0
#define ESC_HW4_CURRENT_THRESHOLD 10
#define ESC_HW4_VOLTAGE_MULTIPLIER 0.0088
#define ESC_HW4_CURRENT_MULTIPLIER 0.3
#define ESC_HW4_CURRENT_MAX 250

/* Fuel flow sensor */
#define ENABLE_FUEL_FLOW false
#define FUEL_FLOW_ML_PER_MINUTE 0.01

/* Fuel pressure */
#define XGZP68XXD_K 64

/* GPIO */
#define GPIO_INTERVAL_MS 1000
#define GPIO_MASK 0

/* GPS */
#define GPS_RATE 1

/* Gyro */
#define GYRO_ADDRESS 0x68    // 0x68 or 0x69
#define ACCEL_SENSITIVITY 0  // 0 = 2g, 1 = 4g, 2 = 8g, 3 = 16g
#define GYRO_SENSITIVITY 0   // 0 = 250 dps, 1 = 500 dps, 2 = 1000 dps, 3 = 2000 dps
#define GYRO_WEIGHTING 96    // 0 - 100%
#define GYRO_FILTER 0        // 0 = no filter, 1 = 184Hz, 2 = 92Hz, 3 = 41Hz, 4 = 20Hz, 5 = 10Hz, 6 = 5Hz

/* INA3221 */
#define INA3221_FILTER 1  // 1 - 1024
#define INA3221_CELLS 3   // 1 to 12

#define SENSOR_ID_SRXL2 1 // Sensor Id for SRXL2 protocol (if used). 1-15

#define NTC_OFFSET 0

config_t *config_read() {
    uint16_t *version = (uint16_t *)(XIP_BASE + CONFIG_FLASH_TARGET_OFFSET);
    if (*version != CONFIG_VERSION) {
        uint16_t *version_old = (uint16_t *)(XIP_BASE + CONFIG_OLD_FLASH_TARGET_OFFSET);
        if (*version_old == CONFIG_VERSION) {
            // migrate old config
            uint8_t flash[FLASH_PAGE_SIZE] = {0};
            memcpy(flash, (uint8_t *)version_old, sizeof(config_t));
            uint32_t ints = save_and_disable_interrupts();
            flash_range_erase(CONFIG_FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE);
            flash_range_program(CONFIG_FLASH_TARGET_OFFSET, flash, FLASH_PAGE_SIZE);
            restore_interrupts(ints);
        } else {
            // write default config
            config_forze_write();
        }
    }
    return (config_t *)(XIP_BASE + CONFIG_FLASH_TARGET_OFFSET);
}

void config_write(config_t *config) {
    uint8_t flash[FLASH_PAGE_SIZE] = {0};
    memcpy(flash, (uint8_t *)config, sizeof(config_t));
    uint32_t ints = save_and_disable_interrupts();
    flash_range_erase(CONFIG_FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE);
    flash_range_program(CONFIG_FLASH_TARGET_OFFSET, flash, FLASH_PAGE_SIZE);
    restore_interrupts(ints);
}

void config_get(config_t *config) {
    memcpy(config, (config_t *)(XIP_BASE + CONFIG_FLASH_TARGET_OFFSET), sizeof(config_t));
    config->debug = MSRC_DEBUG;
}

void config_forze_write() {
    config_t config = {0};
    config.version = CONFIG_VERSION;
    config.rx_protocol = RX_PROTOCOL;
    config.esc_protocol = ESC_PROTOCOL;
    config.enable_gps = ENABLE_GPS;
    config.gps_baudrate = GPS_BAUD_RATE;
    config.enable_analog_voltage = ENABLE_ANALOG_VOLTAGE;
    config.enable_analog_current = ENABLE_ANALOG_CURRENT;
    config.enable_analog_ntc = ENABLE_ANALOG_NTC;
    config.enable_analog_airspeed = ENABLE_ANALOG_AIRSPEED;
    config.i2c_module = I2C1_TYPE;
    config.alpha_rpm = ALPHA(AVERAGING_ELEMENTS_RPM);
    config.alpha_voltage = ALPHA(AVERAGING_ELEMENTS_VOLTAGE);
    config.alpha_current = ALPHA(AVERAGING_ELEMENTS_CURRENT);
    config.alpha_temperature = ALPHA(AVERAGING_ELEMENTS_TEMPERATURE);
    config.alpha_vario = ALPHA(AVERAGING_ELEMENTS_VARIO);
    config.alpha_airspeed = ALPHA(AVERAGING_ELEMENTS_AIRSPEED);
    config.refresh_rate_rpm = REFRESH_RATE_RPM;
    config.refresh_rate_voltage = REFRESH_RATE_VOLTAGE;
    config.refresh_rate_current = REFRESH_RATE_CURRENT;
    config.refresh_rate_temperature = REFRESH_RATE_TEMPERATURE;
    config.refresh_rate_gps = REFRESH_RATE_GPS;
    config.refresh_rate_consumption = REFRESH_RATE_CONSUMPTION;
    config.refresh_rate_vario = REFRESH_RATE_VARIO;
    config.refresh_rate_airspeed = REFRESH_RATE_AIRSPEED;
    config.refresh_rate_default = REFRESH_RATE_DEFAULT;
    config.analog_voltage_multiplier = ANALOG_VOLTAGE_MULTIPLIER;
    config.analog_current_multiplier = ANALOG_CURRENT_MULTIPLIER;
    config.analog_current_offset = ANALOG_CURRENT_OFFSET;
    config.analog_current_autoffset = ANALOG_CURRENT_AUTO_OFFSET;
    config.pairOfPoles = RPM_PAIR_OF_POLES;
    config.mainTeeth = RPM_MAIN_TEETH;
    config.pinionTeeth = RPM_PINION_TEETH;
    config.rpm_multiplier = RPM_PINION_TEETH / (1.0 * RPM_MAIN_TEETH * RPM_PAIR_OF_POLES);
    config.bmp280_filter = BMP280_FILTER;
    config.enable_pwm_out = ENABLE_PWM_OUT;
    config.smartport_sensor_id = SMARTPORT_SENSOR_ID;
    config.smartport_data_id = SMARTPORT_DATA_ID;
    config.vario_auto_offset = VARIO_AUTO_OFFSET;
    config.xbus_clock_stretch = XBUS_CLOCK_STRECH_SWITCH;
    config.jeti_gps_speed_units_kmh = JETI_GPS_SPEED_UNITS_KMH;
    config.enable_esc_hw4_init_delay = ENABLE_ESC_INIT_DELAY;
    config.esc_hw4_init_delay_duration = ESC_INIT_DELAY_DURATION;
    config.esc_hw4_current_thresold = ESC_HW4_CURRENT_THRESHOLD;
    config.esc_hw4_current_max = ESC_HW4_CURRENT_MAX;
    config.esc_hw4_voltage_multiplier = ESC_HW4_VOLTAGE_MULTIPLIER;
    config.esc_hw4_current_multiplier = ESC_HW4_CURRENT_MULTIPLIER;
    config.ibus_alternative_coordinates = IBUS_GPS_ALTERNATIVE_COORDINATES;
    config.debug = MSRC_DEBUG;
    config.esc_hw4_is_manual_offset = ESC_HW4_MANUAL_OFFSET;
    config.esc_hw4_offset = ESC_HW4_CURRENT_OFFSET;
    config.xbus_use_alternative_volt_temp = XBUS_ALTERNATIVE_VOLT_TEMP;
    config.serial_monitor_baudrate = SERIAL_MONITOR_BAUDRATE;
    config.serial_monitor_stop_bits = SERIAL_MONITOR_STOPBITS;
    config.serial_monitor_parity = SERIAL_MONITOR_PARITY;
    config.serial_monitor_timeout_ms = SERIAL_MONITOR_TIMEOUT_MS;
    config.serial_monitor_inverted = SERIAL_MONITOR_INVERTED;
    config.airspeed_offset = AIRSPEED_OFFSET;
    config.airspeed_vcc = AIRSPEED_VCC * 100;
    config.fuel_flow_ml_per_pulse = FUEL_FLOW_ML_PER_MINUTE;
    config.enable_fuel_flow = ENABLE_FUEL_FLOW;
    config.enable_fuel_pressure = false;
    config.xgzp68xxd_k = XGZP68XXD_K;
    config.serial_monitor_format = SERIAL_MONITOR_FORMAT;
    config.serial_monitor_gpio = SERIAL_MONITOR_GPIO;
    config.gps_rate = GPS_RATE;
    config.gpio_interval = GPIO_INTERVAL_MS;
    config.gpio_mask = GPIO_MASK;
    config.sbus_battery_slot = true;
    config.fport_inverted = false;
    config.esc_hw4_auto_detect = true;
    config.enable_gyro = false;
    config.mpu6050_acc_scale = ACCEL_SENSITIVITY;
    config.mpu6050_gyro_scale = GYRO_SENSITIVITY;
    config.mpu6050_gyro_weighting = GYRO_WEIGHTING;
    //config.gyro_rate = GYRO_RATE;
    config.ina3221_filter = INA3221_FILTER;
    config.lipo_cells = INA3221_CELLS;
    config.enable_lipo = false;
    config.sensor_id_srxl2 = SENSOR_ID_SRXL2;
    config.ntc_offset = NTC_OFFSET;
    config_write(&config);
}

================================================
FILE: board/project/config.h
================================================
#ifndef CONFIG_H
#define CONFIG_H

#include "common.h"

#define CONFIG_FORZE_WRITE false
#define CONFIG_VERSION 2
#define CONFIG_FLASH_TARGET_OFFSET (768 * 1024)  // 768kB after start of flash. Program (uf2) max size 768kB

extern context_t context;

config_t *config_read();
void config_write(config_t *config);
void config_forze_write();
void config_get(config_t *config);

#endif

================================================
FILE: board/project/constants.h
================================================
#ifndef CONSTANTS_H
#define CONSTANTS_H

/* Pins */
#define UART0_TX_GPIO 0       // receiver rx
#define UART0_RX_GPIO 1       // receiver tx
#define I2C1_SDA_GPIO 2       // receiver sda (with pull up)
#define I2C1_SCL_GPIO 3       // receiver scl (with pull up)
#define UART1_TX_GPIO 4       // not used
#define UART1_RX_GPIO 5       // esc tx
#define PWM_CAPTURE_GPIO 4    // pwm (rpm)
#define CASTLE_PWM_GPIO 4     // receiver throttle signal
#define CASTLE_ESC_GPIO 5     // esc throttle signal
#define UART_TX_PIO_GPIO 14   // gps rx
#define UART_RX_PIO_GPIO 6    // gps tx
#define CLOCK_STRETCH_GPIO 7  // npn switch
#define I2C0_SDA_GPIO 8       // i2c module (vario)
#define I2C0_SCL_GPIO 9       // i2c module (vario)
#define PWM_OUT_GPIO 10       // pwm out
#define FUELMETER_CAPTURE_GPIO 11   // fuel meter (pwm in)
#define ADC0_GPIO 26          // Voltage
#define ADC1_GPIO 27          // Current
#define ADC2_GPIO 28          // NTC
#define ADC3_GPIO 29          // Airspeed
#define SMART_ESC_PWM_GPIO 12 // receiver throttle signal
#define RESTORE_GPIO 15

/* UARTS */
#define UART_RECEIVER uart0
#define UART_RECEIVER_RX UART0_RX_GPIO
#define UART_RECEIVER_TX UART0_TX_GPIO
#define UART_ESC uart1
#define UART_ESC_RX UART1_RX_GPIO
#define UART_ESC_TX UART1_TX_GPIO

// set receiver to uart1 when debugging with probe
// #define UART_RECEIVER uart1
// #define UART_RECEIVER_RX UART1_RX_GPIO
// #define UART_RECEIVER_TX UART1_TX_GPIO

/* ADC */
#define ANALOG_SENSOR_INTERVAL_MS 500
#define BOARD_VCC 3.3
#define ADC_RESOLUTION 4096

/* Stack */
#define STACK_EXTRA 100

#define STACK_RX_IBUS (200 + STACK_EXTRA)
#define STACK_RX_FRSKY_D (654 + STACK_EXTRA)
#define STACK_RX_MULTIPLEX (182 + STACK_EXTRA)
#define STACK_RX_SMARTPORT (190 + STACK_EXTRA)
#define STACK_RX_JETIEX (240 + STACK_EXTRA)
#define STACK_RX_SBUS (220 + STACK_EXTRA)
#define STACK_RX_HITEC (200 + STACK_EXTRA)
#define STACK_RX_XBUS (200 + STACK_EXTRA)
#define STACK_RX_SRXL (200 + STACK_EXTRA)
#define STACK_RX_SRXL2 (300 + STACK_EXTRA)
#define STACK_SERIAL_MONITOR (250 + STACK_EXTRA)
#define STACK_RX_CRSF (292 + STACK_EXTRA)
#define STACK_RX_HOTT (450 + STACK_EXTRA)
#define STACK_RX_SANWA (200 + STACK_EXTRA)
#define STACK_RX_JR_PROPO (300 + STACK_EXTRA)
#define STACK_RX_FPORT (190 + STACK_EXTRA)
#define STACK_RX_FBUS (190 + STACK_EXTRA)
#define STACK_RX_GHST (300 + STACK_EXTRA)
#define STACK_RX_JETIEX_SENSOR (240 + STACK_EXTRA)

#define STACK_SIM_RX (160 + STACK_EXTRA)

#define STACK_SEND_SBUS_PACKET (700 + STACK_EXTRA)

#define STACK_SENSOR_FRSKY_D (164 + STACK_EXTRA)
#define STACK_SENSOR_FRSKY_D_CELL (158 + STACK_EXTRA)
#define STACK_SENSOR_SMARTPORT (180 + STACK_EXTRA)
#define STACK_SENSOR_SMARTPORT_DOUBLE (166 + STACK_EXTRA)
#define STACK_SENSOR_SMARTPORT_COORDINATE (164 + STACK_EXTRA)
#define STACK_SENSOR_SMARTPORT_DATETIME (164 + STACK_EXTRA)
#define STACK_SENSOR_SMARTPORT_CELL (166 + STACK_EXTRA)
#define STACK_SMARTPORT_PACKET_TASK (160 + STACK_EXTRA)
#define STACK_SMARTPORT_SENSOR_VOID_TASK (166 + STACK_EXTRA)

#define STACK_ESC_HW3 (168 + STACK_EXTRA)
#define STACK_ESC_HW4 (250 + STACK_EXTRA)
#define STACK_ESC_HW5 (300 + STACK_EXTRA)
#define STACK_ESC_PWM (160 + STACK_EXTRA)
#define STACK_ESC_CASTLE (500 + STACK_EXTRA)
#define STACK_ESC_KONTRONIK (212 + STACK_EXTRA)
#define STACK_ESC_APD_F (194 + STACK_EXTRA)
#define STACK_ESC_APD_HV (194 + STACK_EXTRA)
#define STACK_SMART_ESC (232 + STACK_EXTRA)
#define STACK_ESC_OMP_M4 (192 + STACK_EXTRA)
#define STACK_ESC_ZTW (202 + STACK_EXTRA)
#define STACK_ESC_OPENYGE (250 + STACK_EXTRA)
#define STACK_GPS (322 + STACK_EXTRA)

#define STACK_VOLTAGE (156 + STACK_EXTRA)
#define STACK_CURRENT (166 + STACK_EXTRA)
#define STACK_NTC (160 + STACK_EXTRA)
#define STACK_AIRSPEED (184 + STACK_EXTRA)
#define STACK_FUEL_METER (200 + STACK_EXTRA)
#define STACK_FUEL_PRESSURE (200 + STACK_EXTRA)
#define STACK_GPIO (150 + STACK_EXTRA)

#define STACK_MPU6050 (252 + STACK_EXTRA)
#define STACK_INA3221 (200 + STACK_EXTRA)

#define STACK_BMP280 (228 + STACK_EXTRA)
#define STACK_MS5611 (172 + STACK_EXTRA)
#define STACK_BMP180 (174 + STACK_EXTRA)

#define STACK_VSPEED (152 + STACK_EXTRA)
#define STACK_DISTANCE (152 + STACK_EXTRA)
#define STACK_CELL_COUNT (180 + STACK_EXTRA)
#define STACK_AUTO_OFFSET (140 + STACK_EXTRA)
#define STACK_PWM_OUT (200 + STACK_EXTRA)

#define STACK_USB (196 + STACK_EXTRA)
#define STACK_LED (186 + STACK_EXTRA)

/* RPM multiplier */
#define RPM_MULTIPLIER (RPM_PINION_TEETH / (1.0 * RPM_MAIN_TEETH * RPM_PAIR_OF_POLES))

/* Averaging elements to alpha */
#define ALPHA(ELEMENTS) (2.0 / ((ELEMENTS) + 1))
/* Averaging alpha to elements */
#define ELEMENTS(ALPHA) (uint) round((2.0 / (ALPHA) - 1))

#endif

================================================
FILE: board/project/dbg_rb.c
================================================
#include "dbg_rb.h"

static uint8_t *s_buf = NULL;
static size_t   s_cap = 0;
static volatile size_t s_head = 0; // write index
static volatile size_t s_tail = 0; // read index

static inline size_t rb_next(size_t idx) {
    return (idx + 1) % s_cap;
}

bool dbg_rb_init(uint8_t *storage, size_t capacity) {
    if (!storage || capacity < 64) return false;
    s_buf = storage;
    s_cap = capacity;
    s_head = 0;
    s_tail = 0;
    return true;
}

size_t dbg_rb_available(void) {
    size_t head = s_head;
    size_t tail = s_tail;
    if (head >= tail) return head - tail;
    return (s_cap - tail) + head;
}

size_t dbg_rb_free(void) {
    // One byte is left unused to distinguish full vs empty.
    return (s_cap - 1) - dbg_rb_available();
}

size_t dbg_rb_push(const uint8_t *data, size_t len) {
    if (!s_buf || !data || len == 0) return 0;

    size_t written = 0;
    while (written < len) {
        // If next head equals tail, buffer is full.
        size_t next = rb_next(s_head);
        if (next == s_tail) break;
        s_buf[s_head] = data[written++];
        s_head = next;
    }
    return written;
}

size_t dbg_rb_pop(uint8_t *out, size_t len) {
    if (!s_buf || !out || len == 0) return 0;

    size_t read = 0;
    while (read < len) {
        if (s_tail == s_head) break; // empty
        out[read++] = s_buf[s_tail];
        s_tail = rb_next(s_tail);
    }
    return read;
}

================================================
FILE: board/project/dbg_rb.h
================================================
#pragma once

#include <stddef.h>
#include <stdint.h>
#include <stdbool.h>

#ifdef __cplusplus
extern "C" {
#endif

// Ring buffer init. capacity must be >= 64 and power-of-two recommended.
bool dbg_rb_init(uint8_t *storage, size_t capacity);

// Write raw bytes into RB. Returns number of bytes written (may be < len if full).
size_t dbg_rb_push(const uint8_t *data, size_t len);

// Pop up to len bytes. Returns number of bytes popped.
size_t dbg_rb_pop(uint8_t *out, size_t len);

// How many bytes currently stored.
size_t dbg_rb_available(void);

// Free space remaining.
size_t dbg_rb_free(void);

#ifdef __cplusplus
}
#endif

================================================
FILE: board/project/dbg_task.c
================================================
// dbg_task.c

#include "dbg_task.h"
#include "dbg_rb.h"

#include <stdio.h>
#include <stdarg.h>
#include <string.h>

#include "FreeRTOS.h"
#include "task.h"

// -------- config --------
#ifndef DBG_RB_CAPACITY
#define DBG_RB_CAPACITY 2048u
#endif

#ifndef DBG_PRINTF_TMP
#define DBG_PRINTF_TMP 256u
#endif

#ifndef DBG_FLUSH_CHUNK
#define DBG_FLUSH_CHUNK 64u
#endif
// ------------------------

static TaskHandle_t s_dbg_task = NULL;

// Static RB storage
static uint8_t s_rb_storage[DBG_RB_CAPACITY];

static void dbg_notify(void) {
    if (s_dbg_task) {
        (void)xTaskNotifyGive(s_dbg_task);
    }
}

void dbg_task_init(void) {
    // Safe to call multiple times
    static bool inited = false;
    if (inited) return;
    inited = true;
    (void)dbg_rb_init(s_rb_storage, sizeof(s_rb_storage));
}

static void dbg_task_fn(void *arg) {
    (void)arg;
    uint8_t chunk[DBG_FLUSH_CHUNK];

    for (;;) {
        // Wait until something is written, but also wake periodically.
        (void)ulTaskNotifyTake(pdTRUE, pdMS_TO_TICKS(50));

        // Drain RB
        while (dbg_rb_available() > 0) {
            size_t n = dbg_rb_pop(chunk, sizeof(chunk));
            for (size_t i = 0; i < n; i++) {
                // Use putchar to avoid heavy printf parsing.
                putchar((int)chunk[i]);
            }
            // Optional: flush stdio if your backend needs it
            // fflush(stdout);
            taskYIELD();
        }
    }
}

void dbg_task_start(unsigned stack_words, unsigned priority) {
    dbg_task_init();

    if (s_dbg_task) return; // already started

    (void)xTaskCreate(
        dbg_task_fn,
        "dbg",
        (configSTACK_DEPTH_TYPE)stack_words,
        NULL,
        (UBaseType_t)priority,
        &s_dbg_task
    );
}

int dbg_write(const char *fmt, ...) {
    if (!fmt) return 0;

    char tmp[DBG_PRINTF_TMP];

    va_list ap;
    va_start(ap, fmt);
    int n = vsnprintf(tmp, sizeof(tmp), fmt, ap);
    va_end(ap);

    if (n <= 0) return n;

    // If truncated, n is the number that *would* have been written.
    size_t to_write = (size_t)n;
    if (to_write >= sizeof(tmp)) {
        to_write = sizeof(tmp) - 1; // write truncated content
    }

    (void)dbg_rb_push((const uint8_t *)tmp, to_write);
    dbg_notify();
    return n;
}

void dbg_write_buffer(const uint8_t *buffer, size_t length, const char *format) {
    if (!buffer || length == 0 || !format) return;

    // Format each byte into a small temp then push.
    // Keep this small to avoid big stack usage.
    char tmp[32];

    for (size_t i = 0; i < length; i++) {
        int n = snprintf(tmp, sizeof(tmp), format, buffer[i]);
        if (n > 0) {
            size_t to_write = (size_t)n;
            if (to_write >= sizeof(tmp)) to_write = sizeof(tmp) - 1;
            (void)dbg_rb_push((const uint8_t *)tmp, to_write);
        }
    }

    dbg_notify();
}

================================================
FILE: board/project/dbg_task.h
================================================
#pragma once

#include <stddef.h>
#include <stdint.h>

#ifdef __cplusplus
extern "C" {
#endif

// Must be called once at boot, after scheduler init but before using debug macros is ok too.
void dbg_task_init(void);

// Start the debug task. Call once after scheduler start context is ready.
// stack_words: FreeRTOS words, not bytes. priority: low (e.g. 1).
void dbg_task_start(unsigned stack_words, unsigned priority);

// printf-like write into ring buffer + notify debug task.
int dbg_write(const char *fmt, ...);

// Write an array into ring buffer with per-byte formatting (no prefix).
// Example format: "%02X " or "%u," etc. You control separators.
void dbg_write_buffer(const uint8_t *buffer, size_t length, const char *format);

#ifdef __cplusplus
}
#endif

================================================
FILE: board/project/led.c
================================================
#include "led.h"

#include "pico/stdlib.h"
#include "ws2812.h"

void led_task() {
    const uint WS2812_PIN = 16;
    gpio_init(PICO_DEFAULT_LED_PIN);
    gpio_set_dir(PICO_DEFAULT_LED_PIN, GPIO_OUT);
    ws2812_init(pio0, WS2812_PIN, 800000);

    while (1) {
        for (uint8_t i = context.led_cycles; i > 0; i--) {
            gpio_put(PICO_DEFAULT_LED_PIN, 1);
            put_pixel_rgb(0, 0, 100);
            vTaskDelay(context.led_cycle_duration / 2 / portTICK_PERIOD_MS);
            gpio_put(PICO_DEFAULT_LED_PIN, 0);
            put_pixel_rgb(0, 0, 0);
            vTaskDelay(context.led_cycle_duration / 2 / portTICK_PERIOD_MS);
        }
        vTaskSuspend(NULL);
    }
}

================================================
FILE: board/project/led.h
================================================
#ifndef LED_H
#define LED_H

#include "common.h"

extern context_t context;

void led_task();

#endif

================================================
FILE: board/project/main.c
================================================
#include <stdio.h>

#include "config.h"
#include "frsky_d.h"
#include "hitec.h"
#include "ibus.h"
#include "jetiex.h"
#include "led.h"
#include "multiplex.h"
#include "sbus.h"
#include "serial_monitor.h"
#include "sim_rx.h"
#include "smartport.h"
#include "srxl.h"
#include "srxl2.h"
#include "usb.h"
#include "xbus.h"
#include "crsf.h"
#include "hott.h"
#include "sanwa.h"
#include "jr_dmss.h"
#include "fport.h"
#include "fbus.h"
#include "ghst.h"
#include "jetiex_sensor.h"
#include "dbg_task.h"

context_t context;

void vApplicationStackOverflowHook(TaskHandle_t xTask, char *pcTaskName) {
    printf("stack overflow %p %s\r\n", xTask, pcTaskName);
    while (1)
        ;
}

int main() {
    stdio_init_all();

    gpio_init(RESTORE_GPIO);
    gpio_pull_up(RESTORE_GPIO);
    if (CONFIG_FORZE_WRITE || !gpio_get(RESTORE_GPIO)) config_forze_write();
    config_t *config = config_read();

    context.debug = config->debug;
    if (context.debug) sleep_ms(1000);

    xTaskCreate(usb_task, "usb_task", STACK_USB, NULL, 1, &context.usb_task_handle);

    dbg_task_init();
    dbg_task_start(512, 1);

    debug("\n\nMSRC init");

    context.led_cycle_duration = 200;
    context.led_cycles = 3;
    xTaskCreate(led_task, "led_task", STACK_LED, NULL, 1, &context.led_task_handle);

    switch (config->rx_protocol) {
        case RX_XBUS:
            xTaskCreate(xbus_task, "xbus_task", STACK_RX_XBUS, NULL, 3, &context.receiver_task_handle);
            break;
        case RX_IBUS:
            xTaskCreate(ibus_task, "ibus_task", STACK_RX_IBUS, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_FRSKY_D:
            xTaskCreate(frsky_d_task, "frsky_d_task", STACK_RX_FRSKY_D, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_MULTIPLEX:
            xTaskCreate(multiplex_task, "multiplex_task", STACK_RX_MULTIPLEX, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_SMARTPORT:
            xTaskCreate(smartport_task, "smartport_task", STACK_RX_SMARTPORT, NULL, 4, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_JETIEX:
            xTaskCreate(jetiex_task, "jetiex_task", STACK_RX_JETIEX, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_SBUS:
            xTaskCreate(sbus_task, "sbus_task", STACK_RX_SBUS, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_HITEC:
            xTaskCreate(hitec_task, "hitec_task", STACK_RX_HITEC, NULL, 3, &context.receiver_task_handle);
            break;
        case RX_SRXL:
            xTaskCreate(srxl_task, "srxl_task", STACK_RX_SRXL, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_SRXL2:
            xTaskCreate(srxl2_task, "srxl2_task", STACK_RX_SRXL2, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case SERIAL_MONITOR:
            xTaskCreate(serial_monitor_task, "serial_monitor", STACK_SERIAL_MONITOR, NULL, 3,
                        &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            context.uart1_notify_task_handle = context.receiver_task_handle;
            context.uart_pio_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_CRSF:
            xTaskCreate(crsf_task, "crfs_task", STACK_RX_CRSF, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_HOTT:
            xTaskCreate(hott_task, "hott_task", STACK_RX_HOTT, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_SANWA:
            xTaskCreate(sanwa_task, "sanwa_task", STACK_RX_SANWA, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_JR_PROPO:
            xTaskCreate(jr_dmss_task, "jr_dmss_task", STACK_RX_JR_PROPO, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_FPORT:
            xTaskCreate(fport_task, "fport_task", STACK_RX_FPORT, NULL, 4, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_FBUS:
            xTaskCreate(fbus_task, "fbus_task", STACK_RX_FBUS, NULL, 4, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_GHST:
            xTaskCreate(ghst_task, "ghst_task", STACK_RX_GHST, NULL, 3, &context.receiver_task_handle);
            context.uart0_notify_task_handle = context.receiver_task_handle;
            break;
        case RX_JETIEX_SENSOR:
            xTaskCreate(jetiex_sensor_task, "jetiex_sensor_task", STACK_RX_JETIEX_SENSOR, NULL, 3, &context.receiver_task_handle);
            context.uart_pio_notify_task_handle = context.receiver_task_handle;
            break;
    }

#ifdef SIM_RX
    sim_rx_parameters_t parameter = {config->rx_protocol};
    xTaskCreate(sim_rx_task, "sim_rx_task", STACK_SIM_RX, &parameter, 3, NULL);
#endif

    vTaskStartScheduler();

    while (1)
        ;
}


================================================
FILE: board/project/pio/CMakeLists.txt
================================================
target_sources(${PROJECT_NAME} PRIVATE
    capture_edge.c
    castle_link.c
    i2c_multi.c
    uart_rx.c
    ws2812.c
    uart_tx.c
)

target_link_libraries(${PROJECT_NAME} 
    pico_stdlib
    hardware_irq
    hardware_pio
    hardware_clocks
    hardware_dma
)

pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/capture_edge.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/i2c_multi.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/uart_rx.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/uart_tx.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/castle_link.pio)
pico_generate_pio_header(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/ws2812.pio)


================================================
FILE: board/project/pio/capture_edge.c
================================================
/*
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree.
 *
 * Library for pin capture timer for RP2040
 */

#include "capture_edge.h"

#include <stdio.h>

#include "hardware/dma.h"
#include "hardware/irq.h"

#define MAX_PIN_COUNT 2

static uint pins_, counter_;
static const uint reload_counter_ = 0xffffffff, reload_pins_ = 1;
static uint sm_, offset_, dma_channel_write_pins_, dma_channel_write_counter_, dma_channel_counter_,
    dma_channel_reload_counter_, dma_channel_reload_pins_, dma_channel_reload_write_counter_, pin_count_;
static PIO pio_;
static void (*handler_[MAX_PIN_COUNT])(uint counter, edge_type_t edge) = {NULL};

static inline void handler_pio(void);
static inline edge_type_t get_captured_edge(uint pin, uint pins, uint prev);
static inline uint bit_value(uint pos);

void capture_edge_init(PIO pio, uint pin_base, uint pin_count, float clk_div, uint irq) {
    pio_ = pio;
    pin_count_ = pin_count;

    // pio capture
    sm_ = pio_claim_unused_sm(pio_, true);
    offset_ = pio_add_program(pio_, &capture_edge_program);
    pio_sm_set_consecutive_pindirs(pio_, sm_, pin_base, pin_count, false);
    pio_sm_config c = capture_edge_program_get_default_config(offset_);
    sm_config_set_clkdiv(&c, clk_div);
    sm_config_set_in_pins(&c, pin_base);
    pio->instr_mem[offset_ + 3] = pio_encode_in(pio_pins, pin_count);
    pio->instr_mem[offset_ + 4] = pio_encode_in(pio_null, 32 - pin_count);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
    if (irq == PIO0_IRQ_0 || irq == PIO1_IRQ_0)
        pio_set_irq0_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + CAPTURE_EDGE_IRQ_NUM), true);
    else
        pio_set_irq1_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + CAPTURE_EDGE_IRQ_NUM), true);
    pio_interrupt_clear(pio_, CAPTURE_EDGE_IRQ_NUM);
    pio_sm_init(pio_, sm_, offset_ + capture_edge_offset_start, &c);
    irq_set_exclusive_handler(irq, handler_pio);
    irq_set_enabled(irq, true);

    // get dma channels
    dma_channel_write_pins_ = dma_claim_unused_channel(true);
    dma_channel_write_counter_ = dma_claim_unused_channel(true);
    dma_channel_counter_ = dma_claim_unused_channel(true);
    dma_channel_reload_counter_ = dma_claim_unused_channel(true);
    dma_channel_reload_pins_ = dma_claim_unused_channel(true);
    dma_channel_reload_write_counter_ = dma_claim_unused_channel(true);

    // dma channel write pins
    dma_channel_config config_dma_channel_write_pins = dma_channel_get_default_config(dma_channel_write_pins_);
    channel_config_set_transfer_data_size(&config_dma_channel_write_pins, DMA_SIZE_32);
    channel_config_set_write_increment(&config_dma_channel_write_pins, false);
    channel_config_set_read_increment(&config_dma_channel_write_pins, false);
    channel_config_set_dreq(&config_dma_channel_write_pins, pio_get_dreq(pio_, sm_, false));
    channel_config_set_chain_to(&config_dma_channel_write_pins, dma_channel_reload_pins_);
    dma_channel_configure(dma_channel_write_pins_, &config_dma_channel_write_pins,
                          &pins_,           // write address
                          &pio_->rxf[sm_],  // read address
                          1, false);

    // dma channel write counter
    dma_channel_config config_dma_channel_write_counter = dma_channel_get_default_config(dma_channel_write_counter_);
    channel_config_set_transfer_data_size(&config_dma_channel_write_counter, DMA_SIZE_32);
    channel_config_set_write_increment(&config_dma_channel_write_counter, false);
    channel_config_set_read_increment(&config_dma_channel_write_counter, false);
    channel_config_set_dreq(&config_dma_channel_write_pins, pio_get_dreq(pio_, sm_, false));
    channel_config_set_chain_to(&config_dma_channel_write_counter, dma_channel_reload_write_counter_);
    dma_channel_configure(dma_channel_write_counter_, &config_dma_channel_write_counter,
                          &counter_,                                         // write address
                          &dma_hw->ch[dma_channel_counter_].transfer_count,  // read address
                          1, false);

    // dma channel counter
    dma_channel_config config_dma_channel_counter = dma_channel_get_default_config(dma_channel_counter_);
    channel_config_set_write_increment(&config_dma_channel_counter, false);
    channel_config_set_read_increment(&config_dma_channel_counter, false);
    uint dma_timer = dma_claim_unused_timer(true);
    dma_timer_set_fraction(dma_timer, 1, COUNTER_CYCLES);
    channel_config_set_dreq(&config_dma_channel_counter, dma_get_timer_dreq(dma_timer));
    channel_config_set_chain_to(&config_dma_channel_counter, dma_channel_reload_counter_);
    dma_channel_configure(dma_channel_counter_, &config_dma_channel_counter,
                          NULL,  // write address
                          NULL,  // read address
                          0xffffffff, false);

    // dma channel reload counter
    dma_channel_config config_dma_channel_reload_counter = dma_channel_get_default_config(dma_channel_reload_counter_);
    channel_config_set_transfer_data_size(&config_dma_channel_reload_counter, DMA_SIZE_32);
    channel_config_set_write_increment(&config_dma_channel_reload_counter, false);
    channel_config_set_read_increment(&config_dma_channel_reload_counter, false);
    dma_channel_configure(dma_channel_reload_counter_, &config_dma_channel_reload_counter,
                          &dma_hw->ch[dma_channel_counter_].al1_transfer_count_trig,  // write address
                          &reload_counter_,                                           // read address
                          1, false);

    // dma channel reload pins
    dma_channel_config config_dma_channel_reload_pins = dma_channel_get_default_config(dma_channel_reload_pins_);
    channel_config_set_transfer_data_size(&config_dma_channel_reload_pins, DMA_SIZE_32);
    channel_config_set_write_increment(&config_dma_channel_reload_pins, false);
    channel_config_set_read_increment(&config_dma_channel_reload_pins, false);
    dma_channel_configure(dma_channel_reload_pins_, &config_dma_channel_reload_pins,
                          &dma_hw->ch[dma_channel_write_pins_].al1_transfer_count_trig,  // write address
                          &reload_pins_,                                                 // read address
                          1, false);

    // dma channel reload write counter
    dma_channel_config config_dma_channel_reload_write_counter =
    dma_channel_get_default_config(dma_channel_reload_write_counter_);
    channel_config_set_transfer_data_size(&config_dma_channel_reload_write_counter, DMA_SIZE_32);
    channel_config_set_write_increment(&config_dma_channel_reload_write_counter, false);
    channel_config_set_read_increment(&config_dma_channel_reload_write_counter, false);
    dma_channel_configure(dma_channel_reload_write_counter_, &config_dma_channel_reload_write_counter,
                          &dma_hw->ch[dma_channel_write_counter_].al1_transfer_count_trig,  // write address
                          &reload_pins_,                                                    // read address
                          1, false);

    dma_start_channel_mask((1 << dma_channel_write_pins_) | (1 << dma_channel_write_counter_) |
                           (1 << dma_channel_counter_));
    pio_sm_set_enabled(pio_, sm_, true);
}

void capture_edge_set_handler(uint pin, capture_handler_t handler) {
    if (pin < pin_count_) {
        handler_[pin] = handler;
    }
}

void capture_edge_remove(void) {
    for (uint pin = 0; pin < pin_count_; pin++) capture_edge_set_handler(pin, NULL);
    pio_remove_program(pio_, &capture_edge_program, offset_);
    pio_sm_unclaim(pio_, sm_);
    dma_channel_unclaim(dma_channel_write_pins_);
    dma_channel_unclaim(dma_channel_write_counter_);
    dma_channel_unclaim(dma_channel_counter_);
    dma_channel_unclaim(dma_channel_reload_counter_);
    dma_channel_unclaim(dma_channel_reload_pins_);
    dma_channel_unclaim(dma_channel_reload_write_counter_);
}

static inline void handler_pio(void) {
    static uint prev_pins = 0;
    uint counter = ~counter_;
    uint pins = pins_;
    for (uint pin = 0; pin < pin_count_; pin++) {
        edge_type_t edge = get_captured_edge(pin, pins, prev_pins);
        if (edge && *handler_[pin]) handler_[pin](counter, edge);
    }
    prev_pins = pins;
    pio_interrupt_clear(pio_, CAPTURE_EDGE_IRQ_NUM);
}

static inline edge_type_t get_captured_edge(uint pin, uint pins, uint prev) {
    if ((bit_value(pin) & pins) ^ (bit_value(pin) & prev) && (bit_value(pin) & pins)) return EDGE_RISE;
    if ((bit_value(pin) & pins) ^ (bit_value(pin) & prev) && !(bit_value(pin) & pins)) return EDGE_FALL;
    return EDGE_NONE;
}

static inline uint bit_value(uint pos) { return 1 << pos; }


================================================
FILE: board/project/pio/capture_edge.h
================================================
/*
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree.
 *
 * Library for pin capture timer for RP2040
 */

#ifndef CAPTURE_EDGE
#define CAPTURE_EDGE

#ifdef __cplusplus
extern "C" {
#endif

#include "capture_edge.pio.h"
#include "hardware/pio.h"

typedef enum edge_type_t { EDGE_NONE, EDGE_FALL, EDGE_RISE } edge_type_t;

typedef void (*capture_handler_t)(uint counter, edge_type_t edge);

void capture_edge_init(PIO pio, uint pin_base, uint pin_count, float clk_div, uint irq);
void capture_edge_set_handler(uint pin, capture_handler_t handler);
void capture_edge_remove(void);

#ifdef __cplusplus
}
#endif

#endif


================================================
FILE: board/project/pio/capture_edge.pio
================================================
/*
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree. 
 *
 * Library for pin capture timer for RP2040
 */

.define PUBLIC CAPTURE_EDGE_IRQ_NUM 3     // use 0 to 3

.define PUBLIC COUNTER_CYCLES 5

.program capture_edge
capture:
    irq CAPTURE_EDGE_IRQ_NUM
    push
.wrap_target
public start:
    mov y x                         // pins to prev
    nop                             // in pins CAPTURE_EDGE_PIN_COUNT  // read pins
    nop                             // in null ZERO_COUNT
    mov x isr                       // pins to x
    jmp x!=y capture                // capture
.wrap

================================================
FILE: board/project/pio/castle_link.c
================================================
#include "castle_link.h"

#include <math.h>

#include "hardware/irq.h"
#include "hardware/pio.h"
#include "pico/stdlib.h"

static uint sm_pulse_, sm_counter_, offset_pulse_, offset_counter_;
static PIO pio_;
static void (*handler_)(castle_link_telemetry_t packet) = {NULL};

static inline void handler_pio();

void castle_link_init(PIO pio, uint pin, uint irq) {
    pio_ = pio;
    sm_pulse_ = pio_claim_unused_sm(pio_, true);
    offset_pulse_ = pio_add_program(pio_, &pulse_program);
    pio_gpio_init(pio_, pin + 1);
    pio_sm_set_consecutive_pindirs(pio_, sm_pulse_, pin, 2, false);
    pio_sm_set_pins(pio, sm_pulse_, 0);

    pio_sm_config c_pulse = pulse_program_get_default_config(offset_pulse_);
    sm_config_set_clkdiv(&c_pulse, 10);
    sm_config_set_in_pins(&c_pulse, pin);
    sm_config_set_set_pins(&c_pulse, pin + 1, 1);

    pio_sm_init(pio_, sm_pulse_, offset_pulse_, &c_pulse);
    pio_sm_set_enabled(pio_, sm_pulse_, true);

    sm_counter_ = pio_claim_unused_sm(pio_, true);
    offset_counter_ = pio_add_program(pio_, &counter_program);

    pio_sm_config c_counter = counter_program_get_default_config(offset_counter_);
    sm_config_set_clkdiv(&c_counter, 5);
    sm_config_set_in_pins(&c_counter, pin);
    if (irq == PIO0_IRQ_0 || irq == PIO1_IRQ_0)
        pio_set_irq0_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + CASTLE_LINK_IRQ_NUM), true);
    else
        pio_set_irq1_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + CASTLE_LINK_IRQ_NUM), true);
    pio_interrupt_clear(pio_, CASTLE_LINK_IRQ_NUM);
    pio_sm_init(pio_, sm_counter_, offset_counter_ + counter_offset_start, &c_counter);
    pio_sm_set_enabled(pio_, sm_counter_, true);
    irq_set_exclusive_handler(irq, handler_pio);
    irq_set_enabled(irq, true);
}

void castle_link_set_handler(castle_link_handler_t handler) { handler_ = handler; }

void castle_link_remove() {
    castle_link_set_handler(NULL);
    pio_remove_program(pio_, &pulse_program, offset_pulse_);
    pio_remove_program(pio_, &counter_program, offset_counter_);
    pio_sm_unclaim(pio_, sm_pulse_);
    pio_sm_unclaim(pio_, sm_counter_);
}

static inline void handler_pio() {
    static uint index = 0;
    static const float scaler[11] = {0, 20, 4, 50, 1, 0.2502, 20416.7, 4, 4, 30, 63.8125};
    static uint value[12];

    pio_interrupt_clear(pio_, CASTLE_LINK_IRQ_NUM);
    if (pio_sm_is_rx_fifo_full(pio_, sm_counter_)) {
        pio_sm_clear_fifos(pio_, sm_counter_);
        return;
    }
    uint data = pio_sm_get_blocking(pio_, sm_counter_);
    if (data > 50000) {
        index = 0;
        // printf("%i \n", data);
        return;
    }
    if (index > 10) return;
    value[index] = data;
    // printf("(%u)%u ", index, value[index]);
    if (index == 10) {
        uint calibration;
        castle_link_telemetry_t packet;
        if (value[9] < value[10]) {
            calibration = value[0] / 2 + value[9];
            packet.is_temp_ntc = true;
            float temp_raw = ((float)value[10] - calibration / 2) * scaler[10] / calibration;
            packet.temperature =
                1 / (log(temp_raw * 10200.0 / (255.0 - temp_raw) / 10000.0) / 3455.0 + 1.0 / 298.0) - 273.0;
        } else {
            calibration = value[0] / 2 + value[10];
            packet.is_temp_ntc = false;
            packet.temperature = ((float)value[9] - calibration / 2) * scaler[9] / calibration;
        }
        packet.voltage = ((float)value[1] - calibration / 2) * scaler[1] / calibration;
        packet.ripple_voltage = ((float)value[2] - calibration / 2) * scaler[2] / calibration;
        packet.current = ((float)value[3] - calibration / 2) * scaler[3] / calibration;
        packet.thr = ((float)value[4] - calibration / 2) * scaler[4] / calibration;
        packet.output = ((float)value[5] - calibration / 2) * scaler[5] / calibration;
        packet.rpm = ((float)value[6] - calibration / 2) * scaler[6] / calibration;
        packet.voltage_bec = ((float)value[7] - calibration / 2) * scaler[7] / calibration;
        packet.current_bec = ((float)value[8] - calibration / 2) * scaler[8] / calibration;
        if (packet.voltage < 0) packet.voltage = 0;
        if (packet.ripple_voltage < 0) packet.ripple_voltage = 0;
        if (packet.current < 0) packet.current = 0;
        if (packet.thr < 0) packet.thr = 0;
        if (packet.output < 0) packet.output = 0;
        if (packet.rpm < 0) packet.rpm = 0;
        if (packet.voltage_bec < 0) packet.voltage_bec = 0;
        if (packet.current_bec < 0) packet.current_bec = 0;
        if (packet.temperature < 0) packet.temperature = 0;
        handler_(packet);
    }
    index++;
}

================================================
FILE: board/project/pio/castle_link.h
================================================
#ifndef PIO_CASTLE
#define PIO_CASTLE

#include "castle_link.pio.h"

/*                 castle telemetry

    index   element                          scaler
    0       sync
    1       calib 1 (1000us)
    2       Volt (V)                         20
    3       rippleVolt (V)                   4
    4       Curr (A)                         50
    5       Thr (0.1-0.2 ms esc pulse)       1
    6       Output power (%)                 0.2502
    7       rpm                              20416.7
    8       becVolt (V)                      4
    9       becCurr (A)                      4
    10      temp (C) or calib 2 (500us)      30
    11      temp ntc (C) or calib 2 (500us)  63.8125
*/

typedef struct castle_link_telemetry_t {
    float voltage;
    float ripple_voltage;
    float current;
    float thr;
    float output;
    float rpm;
    float voltage_bec;
    float current_bec;
    float temperature;
    bool is_temp_ntc;
} castle_link_telemetry_t;

typedef void (*castle_link_handler_t)(castle_link_telemetry_t packet);

void castle_link_init(PIO pio, uint pin_base, uint irq);
void castle_link_set_handler(castle_link_handler_t handler);
void castle_link_remove();

#endif


================================================
FILE: board/project/pio/castle_link.pio
================================================
/**
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree. 
 */
 
.define PUBLIC CASTLE_LINK_IRQ_NUM 0        // use 0 to 3

// 0 RX input
// 1 PWM input/output
// in base = 0
// set base = 1

.program pulse
.wrap_target
    wait 1 pin 0       // rx pulse start -> esc is output 
    set pindirs 1 [31] // set pin 0 output (1)
    wait 0 pin 0       // end of pwm rx -> esc is input. start counter (irq 4)
    set pindirs 0 [31] // set pin 0 input (0)
    irq 4
.wrap

// 0 RX input
// 1 PWM input
// in base = 0

.program counter  // counter increment every 5 cycles
capture:
    mov isr ~y              // copy counter to isr
    push noblock            // send counter to fifo
    irq CASTLE_LINK_IRQ_NUM  // raise irq
.wrap_target
public start:
    mov y ~null       // init counter
    wait irq 4
loop:
    in pins 2         // read pins
    in null 31        // fill with zeros and shift to esc pin
    mov x isr
    jmp !x capture    // jmp if x=0
    jmp y-- loop      // decrement counter
.wrap

================================================
FILE: board/project/pio/i2c_multi.c
================================================
#include "i2c_multi.h"

#include <stdio.h>
#include <stdlib.h>

#include "hardware/irq.h"
#include "hardware/pio.h"
#include "i2c_multi.pio.h"
#include "pico/stdlib.h"

#define CLK_DIV 16

static i2c_multi_t *i2c_multi;

static void (*receive_handler)(uint8_t data, bool is_address) = NULL;
static void (*request_handler)(uint8_t address) = NULL;
static void (*stop_handler)(uint8_t length) = NULL;

static inline void start_condition_program_init(PIO pio, uint sm, uint offset, uint pin);
static inline void stop_condition_program_init(PIO pio, uint sm, uint offset, uint pin);
static inline void read_byte_program_init(PIO pio, uint sm, uint offset, uint pin);
static inline void write_byte_program_init(PIO pio, uint sm, uint offset, uint pin);
static inline void byte_handler_pio();
static inline void stop_handler_pio();
static inline uint8_t transpond_byte(uint8_t byte);

void i2c_multi_init(PIO pio, uint pin) {
    i2c_multi = (i2c_multi_t *)malloc(sizeof(i2c_multi_t));
    i2c_multi->pio = pio;
    i2c_multi->status = I2C_IDLE;
    i2c_multi->pin = pin;
    i2c_multi->bytes_count = 0;
    i2c_multi_disable_all_addresses();
    i2c_multi->buffer = NULL;
    i2c_multi->buffer_start = NULL;
    uint pio_irq0 = (pio == pio0 ? PIO0_IRQ_0 : PIO1_IRQ_0);
    uint pio_irq1 = (pio == pio0 ? PIO0_IRQ_1 : PIO1_IRQ_1);
    i2c_multi->length = -1;

    pio_gpio_init(pio, pin);
    pio_gpio_init(pio, pin + 1);

    i2c_multi->offset_start = pio_add_program(pio, &start_condition_program);
    i2c_multi->sm_start = pio_claim_unused_sm(pio, true);
    start_condition_program_init(pio, i2c_multi->sm_start, i2c_multi->offset_start, pin);

    i2c_multi->offset_stop = pio_add_program(pio, &stop_condition_program);
    i2c_multi->sm_stop = pio_claim_unused_sm(pio, true);
    stop_condition_program_init(pio, i2c_multi->sm_stop, i2c_multi->offset_stop, pin);

    i2c_multi->offset_read = pio_add_program(pio, &read_byte_program);
    i2c_multi->sm_read = pio_claim_unused_sm(pio, true);
    read_byte_program_init(pio, i2c_multi->sm_read, i2c_multi->offset_read, pin);

    i2c_multi->offset_write = pio_add_program(pio, &write_byte_program);
    i2c_multi->sm_write = pio_claim_unused_sm(pio, true);
    write_byte_program_init(pio, i2c_multi->sm_write, i2c_multi->offset_write, pin);

    pio_sm_put(pio, i2c_multi->sm_read,
               (((uint32_t)do_ack_program_instructions[1]) << 16) | do_ack_program_instructions[0]);
    pio_sm_put(pio, i2c_multi->sm_read,
               (((uint32_t)do_ack_program_instructions[3]) << 16) | do_ack_program_instructions[2]);

    irq_set_exclusive_handler(pio_irq0, byte_handler_pio);
    irq_set_enabled(pio_irq0, true);
    irq_set_exclusive_handler(pio_irq1, stop_handler_pio);
    irq_set_enabled(pio_irq1, true);
}

void i2c_multi_set_write_buffer(uint8_t *buffer) {
    i2c_multi->buffer = buffer;
    i2c_multi->buffer_start = buffer;
}

void i2c_multi_set_receive_handler(i2c_multi_receive_handler_t handler) { receive_handler = handler; }

void i2c_multi_set_request_handler(i2c_multi_request_handler_t handler) { request_handler = handler; }

void i2c_multi_set_stop_handler(i2c_multi_stop_handler_t handler) { stop_handler = handler; }

void i2c_multi_enable_address(uint8_t address) { i2c_multi->address[address / 32] |= 1 << (address % 32); }

void i2c_multi_disable_address(uint8_t address) { i2c_multi->address[address / 32] &= ~(1 << (address % 32)); }

void i2c_multi_enable_all_addresses() {
    i2c_multi->address[0] = 0xFFFFFFFF;
    i2c_multi->address[1] = 0xFFFFFFFF;
    i2c_multi->address[2] = 0xFFFFFFFF;
    i2c_multi->address[3] = 0xFFFFFFFF;
}

void i2c_multi_disable_all_addresses() {
    i2c_multi->address[0] = 0;
    i2c_multi->address[1] = 0;
    i2c_multi->address[2] = 0;
    i2c_multi->address[3] = 0;
}

bool i2c_multi_is_address_enabled(uint8_t address) { return i2c_multi->address[address / 32] & (1 << (address % 32)); }

void i2c_multi_disable() {
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_read, false);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_write, false);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_start, false);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_stop, false);
    pio_sm_clear_fifos(i2c_multi->pio, i2c_multi->sm_read);
    pio_sm_clear_fifos(i2c_multi->pio, i2c_multi->sm_write);
    gpio_set_input_enabled(i2c_multi->pin, true);
    gpio_set_input_enabled(i2c_multi->pin + 1, true);
    i2c_multi->bytes_count = 0;
    i2c_multi->status = I2C_IDLE;
    i2c_multi->buffer = i2c_multi->buffer_start;
}

void i2c_multi_restart() {
    i2c_multi_disable();
    pio_sm_restart(i2c_multi->pio, i2c_multi->sm_start);
    pio_sm_restart(i2c_multi->pio, i2c_multi->sm_stop);
    pio_sm_restart(i2c_multi->pio, i2c_multi->sm_read);
    pio_sm_restart(i2c_multi->pio, i2c_multi->sm_write);
    pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
               (((uint32_t)do_ack_program_instructions[1]) << 16) | do_ack_program_instructions[0]);
    pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
               (((uint32_t)do_ack_program_instructions[3]) << 16) | do_ack_program_instructions[2]);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_read, true);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_write, true);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_start, true);
    pio_sm_set_enabled(i2c_multi->pio, i2c_multi->sm_stop, true);
}

void i2c_multi_remove() {
    receive_handler = NULL;
    request_handler = NULL;
    stop_handler = NULL;
    pio_set_irq0_source_enabled(i2c_multi->pio, pis_interrupt0, false);
    pio_set_irq1_source_enabled(i2c_multi->pio, pis_interrupt1, false);
    pio_clear_instruction_memory(i2c_multi->pio);
    pio_sm_unclaim(i2c_multi->pio, i2c_multi->sm_start);
    pio_sm_unclaim(i2c_multi->pio, i2c_multi->sm_stop);
    pio_sm_unclaim(i2c_multi->pio, i2c_multi->sm_read);
    pio_sm_unclaim(i2c_multi->pio, i2c_multi->sm_write);
    i2c_multi->buffer = NULL;
    i2c_multi->buffer_start = NULL;
    i2c_multi->bytes_count = 0;
    i2c_multi->status = I2C_IDLE;
    gpio_set_input_enabled(i2c_multi->pin, true);
    gpio_set_input_enabled(i2c_multi->pin + 1, true);
    free(i2c_multi);
}

void i2c_multi_fixed_length(int16_t length) { i2c_multi->length = length; }

static inline void start_condition_program_init(PIO pio, uint sm, uint offset, uint pin) {
    pio_sm_config c = start_condition_program_get_default_config(offset);
    sm_config_set_in_pins(&c, pin);
    sm_config_set_clkdiv(&c, CLK_DIV);
    sm_config_set_jmp_pin(&c, pin + 1);
    pio_sm_init(pio, sm, offset + start_condition_offset_start, &c);
    pio_sm_set_enabled(pio, sm, true);
}

static inline void stop_condition_program_init(PIO pio, uint sm, uint offset, uint pin) {
    pio_sm_config c = stop_condition_program_get_default_config(offset);
    sm_config_set_in_pins(&c, pin);
    sm_config_set_clkdiv(&c, CLK_DIV);
    sm_config_set_jmp_pin(&c, pin + 1);
    pio_sm_init(pio, sm, offset + stop_condition_offset_start, &c);
    pio_sm_set_enabled(pio, sm, true);
    pio_set_irq1_source_enabled(pio, pis_interrupt1, true);
    pio_interrupt_clear(pio, 1);
}

static inline void read_byte_program_init(PIO pio, uint sm, uint offset, uint pin) {
    pio_sm_config c = read_byte_program_get_default_config(offset);
    sm_config_set_in_pins(&c, pin);
    sm_config_set_clkdiv(&c, CLK_DIV);
    sm_config_set_out_shift(&c, true, true, 32);
    pio_set_irq0_source_enabled(pio, pis_interrupt0, true);
    pio_interrupt_clear(pio, 0);
    sm_config_set_set_pins(&c, pin, 2);
    sm_config_set_sideset_pins(&c, pin);
    pio_sm_init(pio, sm, offset, &c);
    pio_sm_set_enabled(pio, sm, true);
}

static inline void write_byte_program_init(PIO pio, uint sm, uint offset, uint pin) {
    pio_sm_config c = write_byte_program_get_default_config(offset);
    sm_config_set_in_pins(&c, pin);
    sm_config_set_out_pins(&c, pin, 1);
    sm_config_set_set_pins(&c, pin, 2);
    sm_config_set_sideset_pins(&c, pin);
    sm_config_set_clkdiv(&c, CLK_DIV);
    sm_config_set_out_shift(&c, true, true, 32);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
    sm_config_set_jmp_pin(&c, pin);
    pio_sm_init(pio, sm, offset, &c);
    pio_sm_set_enabled(pio, sm, true);
}

static inline void byte_handler_pio() {
    uint8_t received = 0;
    bool is_address = false;
    i2c_multi->bytes_count++;
    if (i2c_multi->status != I2C_WRITE) {
        received = transpond_byte(pio_sm_get_blocking(i2c_multi->pio, i2c_multi->sm_read) >>
                                  24);  // Do the bit-reverse here as PIO instructions are scarce
    }
    if (i2c_multi->status == I2C_IDLE) {
        if (!i2c_multi_is_address_enabled(received >> 1)) {
            i2c_multi->status = I2C_IDLE;
            i2c_multi->bytes_count = 0;
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                       (((uint32_t)do_ack_program_instructions[10] + i2c_multi->offset_read) << 16) |
                           do_ack_program_instructions[9]);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                       (((uint32_t)do_ack_program_instructions[1]) << 16) | do_ack_program_instructions[0]);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                       (((uint32_t)do_ack_program_instructions[3]) << 16) | do_ack_program_instructions[2]);
            pio_interrupt_clear(i2c_multi->pio, 0);
            return;
        }
        if (received & 1) {
            i2c_multi->status = I2C_WRITE;
        } else {
            i2c_multi->status = I2C_READ;
        }
        is_address = true;
    }
    if (i2c_multi->status == I2C_READ) {
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[5]) << 16) | do_ack_program_instructions[4]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[7] + i2c_multi->offset_read) << 16) |
                       do_ack_program_instructions[6]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[1]) << 16) | do_ack_program_instructions[0]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[3]) << 16) | do_ack_program_instructions[2]);
        if (receive_handler) {
            if (is_address) {
                receive_handler(received >> 1, true);
            } else
                receive_handler(received, false);
        }
    }
    if (i2c_multi->status == I2C_WRITE && is_address) {
        if (request_handler) {
            request_handler(received >> 1);
        }
        uint8_t value = 0;
        if (i2c_multi->buffer) {
            value = transpond_byte(*i2c_multi->buffer);
            i2c_multi->buffer++;
        }
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[5]) << 16) | do_ack_program_instructions[4]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[8] + i2c_multi->offset_read) << 16) |
                       do_ack_program_instructions[6]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_read,
                   (((uint32_t)do_ack_program_instructions[1]) << 16) | do_ack_program_instructions[0]);
        pio_sm_put_blocking(i2c_multi->pio, i2c_multi->sm_read,
                            (((uint32_t)do_ack_program_instructions[3]) << 16) | do_ack_program_instructions[2]);

        pio_sm_put(i2c_multi->pio, i2c_multi->sm_write, value);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                   (((uint32_t)wait_ack_program_instructions[1]) << 16) | wait_ack_program_instructions[0]);
        pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                   (((uint32_t)wait_ack_program_instructions[3]) << 16) | wait_ack_program_instructions[2]);
    }
    if (i2c_multi->status == I2C_WRITE && !is_address) {
        if (i2c_multi->length == -1 || (i2c_multi->length > 0 && i2c_multi->bytes_count < i2c_multi->length + 1)) {
            uint8_t value = 0;
            if (i2c_multi->buffer) {
                value = transpond_byte(*i2c_multi->buffer);
                i2c_multi->buffer++;
            }
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                       (((uint32_t)wait_ack_program_instructions[5]) << 16) | wait_ack_program_instructions[4]);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                       (((uint32_t)wait_ack_program_instructions[7] + i2c_multi->offset_write) << 16) |
                           (wait_ack_program_instructions[6]) + i2c_multi->offset_write);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_write, value);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                       (((uint32_t)wait_ack_program_instructions[1]) << 16) | wait_ack_program_instructions[0]);
            pio_sm_put(i2c_multi->pio, i2c_multi->sm_write,
                       (((uint32_t)wait_ack_program_instructions[3]) << 16) | wait_ack_program_instructions[2]);
        } else {
            pio_sm_exec(i2c_multi->pio, i2c_multi->sm_read, i2c_multi->offset_read);
            pio_sm_clear_fifos(i2c_multi->pio, i2c_multi->sm_write);
            pio_sm_exec(i2c_multi->pio, i2c_multi->sm_write, wait_ack_program_instructions[8]);
            pio_sm_exec(i2c_multi->pio, i2c_multi->sm_write,
                        wait_ack_program_instructions[9] + i2c_multi->offset_write);
            if (stop_handler) {
                stop_handler(i2c_multi->bytes_count - 1);
            }
            i2c_multi->bytes_count = 0;
            i2c_multi->status = I2C_IDLE;
        }
    }
    pio_interrupt_clear(i2c_multi->pio, 0);
}

static inline void stop_handler_pio() {
    pio_interrupt_clear(i2c_multi->pio, 1);
    if (i2c_multi->status == I2C_IDLE) return;
    pio_sm_exec(i2c_multi->pio, i2c_multi->sm_read, i2c_multi->offset_read);
    pio_sm_clear_fifos(i2c_multi->pio, i2c_multi->sm_write);
    pio_sm_exec(i2c_multi->pio, i2c_multi->sm_write, wait_ack_program_instructions[8]);
    pio_sm_exec(i2c_multi->pio, i2c_multi->sm_write, wait_ack_program_instructions[9] + i2c_multi->offset_write);
    i2c_multi->buffer = i2c_multi->buffer_start;
    if (stop_handler) {
        stop_handler(i2c_multi->bytes_count - 1);
    }
    i2c_multi->bytes_count = 0;
    i2c_multi->status = I2C_IDLE;
}

static inline uint8_t transpond_byte(uint8_t byte) {
    uint8_t transponded = ((byte & 0x1) << 7) | (((byte & 0x2) >> 1) << 6) | (((byte & 0x4) >> 2) << 5) |
                          (((byte & 0x8) >> 3) << 4) | (((byte & 0x10) >> 4) << 3) | (((byte & 0x20) >> 5) << 2) |
                          (((byte & 0x40) >> 6) << 1) | (((byte & 0x80) >> 7));
    return transponded;
}



================================================
FILE: board/project/pio/i2c_multi.h
================================================
#ifndef I2C_MULTI
#define I2C_MULTI

#include "hardware/pio.h"
#include "common.h"

typedef enum i2c_multi_status_t { I2C_IDLE, I2C_READ, I2C_WRITE } i2c_multi_status_t;

typedef void (*i2c_multi_receive_handler_t)(uint8_t data, bool is_address);
typedef void (*i2c_multi_request_handler_t)(uint8_t address);
typedef void (*i2c_multi_stop_handler_t)(uint8_t length);

typedef struct i2c_multi_t {
    PIO pio;
    uint offset_read, offset_write, sm_read, sm_write, offset_start, offset_stop, sm_start, sm_stop, pin;
    i2c_multi_status_t status;
    uint8_t *buffer, *buffer_start;
    uint8_t bytes_count;
    int16_t length;
    uint address[4];
} i2c_multi_t;

extern context_t context;

void i2c_multi_init(PIO pio, uint pin);
void i2c_multi_set_write_buffer(uint8_t *buffer);
void i2c_multi_set_receive_handler(i2c_multi_receive_handler_t handler);
void i2c_multi_set_request_handler(i2c_multi_request_handler_t handler);
void i2c_multi_set_stop_handler(i2c_multi_stop_handler_t handler);
void i2c_multi_enable_address(uint8_t address);
void i2c_multi_disable_address(uint8_t address);
void i2c_multi_enable_all_addresses();
void i2c_multi_disable_all_addresses();
bool i2c_multi_is_address_enabled(uint8_t address);
void i2c_multi_disable();
void i2c_multi_restart();
void i2c_multi_remove();
void i2c_multi_fixed_length(int16_t length);

#endif


================================================
FILE: board/project/pio/i2c_multi.pio
================================================
/**
 * -------------------------------------------------------------------------------
 * 
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree. 
 * 
 * -------------------------------------------------------------------------------
 * 
 *  I2C slave multi - answer to multiple addresses
 * 
 *  SDA = pin
 *  SCL = pin + 1
 *
 *  Add external pull ups, 1k - 3.3k
 *
 *  Define handlers and write buffer
 * 
 * -------------------------------------------------------------------------------
 */
 
 // sda 0, scl 1

.program start_condition  // 5
do_irq:
    irq 1 // Ensure a stop has been handled, in case this is a repeat start
    irq 4
public start:
.wrap_target
    wait 1 pin 0
    wait 0 pin 0
    jmp pin do_irq
.wrap

.program stop_condition  // 4
do_irq:
    irq 1
public start:
.wrap_target
    wait 0 pin 0
    wait 1 pin 0
    jmp pin do_irq
.wrap

.program read_byte  // 10
.side_set 2 opt pindirs
    wait irq 4
read:
    set x 7 side 0
bit_loop:
    wait 0 pin 1
    wait 1 pin 1
    in pins 1
    jmp x-- bit_loop
    push noblock
do_ack:
    out exec 16
    jmp do_ack
do_irq:
    irq 5

.program do_ack
.side_set 2 opt pindirs
    wait 0 pin 1
    set pins 0 side 3
    nop
    irq wait 0

    set pins 0 side 1
    wait 1 pin 1
    wait 0 pin 1

    // read (receive request)
    jmp 1 

    // write (write request)
    jmp 9

    // address not enabled
    set pindirs 0
    jmp 0

.program write_byte  // 9
.side_set 2 opt pindirs
    wait irq 5
write:
    set x 7 side 1
bit_loop:
    wait 0 pin 1
    out pins 1
    wait 1 pin 1
    jmp x-- bit_loop
    out null 32
wait_ack:
    out exec 16
    jmp wait_ack

.program wait_ack
.side_set 2 opt pindirs
    // clk stretch
    wait 0 pin 1
    nop //set pindirs 2
    set pins 0 side 2
    irq wait 0
    
    // check ack
    nop
    wait 1 pin 1 side 0
    jmp pin 0
    jmp 1

    // stop
    out null 32 side 0
    jmp 0


================================================
FILE: board/project/pio/uart_rx.c
================================================
#include "uart_rx.h"

#include "hardware/clocks.h"
#include "hardware/irq.h"
#include "hardware/pio.h"
#include "pico/stdlib.h"

static uint sm_, offset_;
static PIO pio_;
static void (*handler_)(uint8_t data) = NULL;

static inline void handler_pio(void);

uint uart_rx_init(PIO pio, uint pin, uint baudrate, uint irq) {
    pio_ = pio;
    sm_ = pio_claim_unused_sm(pio_, true);
    pio_sm_set_consecutive_pindirs(pio_, sm_, pin, 1, false);
    pio_gpio_init(pio_, pin);
    gpio_pull_up(pin);

    offset_ = pio_add_program(pio_, &uart_rx_program);
    pio_sm_config c = uart_rx_program_get_default_config(offset_);
    sm_config_set_in_pins(&c, pin);
    sm_config_set_jmp_pin(&c, pin);
    sm_config_set_in_shift(&c, true, false, 32);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_RX);
    float div = (float)clock_get_hz(clk_sys) / (UART_RX_CYCLES_PER_BIT * baudrate);
    sm_config_set_clkdiv(&c, div);

    if (irq == PIO0_IRQ_0 || irq == PIO1_IRQ_0)
        pio_set_irq0_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + UART_RX_IRQ_NUM), true);
    else
        pio_set_irq1_source_enabled(pio_, (enum pio_interrupt_source)(pis_interrupt0 + UART_RX_IRQ_NUM), true);
    pio_interrupt_clear(pio_, UART_RX_IRQ_NUM);

    pio_sm_init(pio_, sm_, offset_, &c);
    pio_sm_set_enabled(pio_, sm_, true);
    irq_set_exclusive_handler(irq, handler_pio);
    irq_set_enabled(irq, true);

    return sm_;
}

void uart_rx_set_handler(uart_rx_handler_t handler) { handler_ = handler; }

void uart_rx_remove(void) {
    uart_rx_set_handler(NULL);
    pio_remove_program(pio_, &uart_rx_program, offset_);
    pio_sm_unclaim(pio_, sm_);
}

static inline void handler_pio(void) {
    pio_interrupt_clear(pio_, UART_RX_IRQ_NUM);
    if (handler_) {
        while (pio_sm_get_rx_fifo_level(pio_, sm_)) {
            uint data = pio_sm_get_blocking(pio_, sm_);
            handler_(data >> 24);
        }
    }
}

================================================
FILE: board/project/pio/uart_rx.h
================================================
#ifndef UART_RX
#define UART_RX

#include "uart_rx.pio.h"

typedef void (*uart_rx_handler_t)(uint8_t data);

uint uart_rx_init(PIO pio, uint pin, uint baudrate, uint irq);
void uart_rx_set_handler(uart_rx_handler_t handler);
void uart_rx_remove();

#endif


================================================
FILE: board/project/pio/uart_rx.pio
================================================
/**
 * Copyright (c) 2022, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree. 
 */

.define PUBLIC UART_RX_IRQ_NUM 2  // use 0 to 3
.define PUBLIC UART_RX_CYCLES_PER_BIT 16  // we want here resolution to reduce the error when sampling. more cycles less error

.program uart_rx  // 1 bit every 16 cycles
start:
    wait 0 pin 0
    set x 7 [16+16/2-2]
bit_loop:
    in pins 1
    jmp x-- bit_loop [16-2]
    jmp pin good_stop
    wait 1 pin 0 [4]
    jmp start
good_stop:
    push
    irq UART_RX_IRQ_NUM


================================================
FILE: board/project/pio/uart_tx.c
================================================
#include "uart_tx.h"

#include "hardware/clocks.h"
#include "hardware/pio.h"
#include "pico/stdlib.h"

static uint sm_, offset_;
static PIO pio_;
static uint8_t data_bits_;
static uint8_t parity_;

uint uart_tx_init(PIO pio, uint pin, uint baudrate, uint data_bits, uint stop_bits, uint parity) {
    pio_ = pio;
    data_bits_ = data_bits;
    parity_ = parity;
    gpio_pull_up(pin);
    sm_ = pio_claim_unused_sm(pio_, true);
    pio_gpio_init(pio_, pin);
    pio_sm_set_consecutive_pindirs(pio_, sm_, pin, 1, false);
    pio_sm_set_pins(pio, sm_, 0xFFFF);
    offset_ = pio_add_program(pio_, &uart_tx_program);
    pio_->instr_mem[offset_] = pio_encode_set(pio_x, parity == UART_PARITY_NONE ? data_bits - 1 : data_bits);
    pio_->instr_mem[offset_ + 6] = pio_encode_set(pio_pins, 1) | pio_encode_delay(16 * stop_bits - 1);
    pio_sm_config c = uart_tx_program_get_default_config(offset_);
    sm_config_set_out_pins(&c, pin, 1);
    sm_config_set_set_pins(&c, pin, 1);
    sm_config_set_in_shift(&c, true, false, 32);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
    float div = (float)clock_get_hz(clk_sys) / (UART_TX_CYCLES_PER_BIT * baudrate);
    sm_config_set_clkdiv(&c, div);
    pio_sm_init(pio_, sm_, offset_, &c);
    pio_sm_set_enabled(pio_, sm_, true);
    return sm_;
}

void uart_tx_write(uint32_t c) {
    if (parity_ != UART_PARITY_NONE) {
        bool parity_bit = 0;
        for (uint i = 0; i < data_bits_; i++) {
            parity_bit ^= (c >> i) & 1;
        }
        c |= (parity_bit << (data_bits_));
        if (parity_ == UART_PARITY_ODD) {
            c ^= (1 << (data_bits_));
        }
    }
    pio_sm_put_blocking(pio_, sm_, c);
}

void uart_tx_write_bytes(void *data, uint8_t length) {
    for (uint8_t i = 0; i < length; i++) {
        switch (data_bits_) {
            case 1 ... 8:
                uart_tx_write(((uint8_t *)data)[i]);
                break;
            case 9 ... 16:
                uart_tx_write(((uint16_t *)data)[i]);
                break;
            case 17 ... 32:
                uart_tx_write(((uint32_t *)data)[i]);
                break;
        }
    }
}

void uart_tx_remove(void) {
    pio_remove_program(pio_, &uart_tx_program, offset_);
    pio_sm_unclaim(pio_, sm_);
}

================================================
FILE: board/project/pio/uart_tx.h
================================================
#ifndef UART_TX
#define UART_TX

#include "uart_tx.pio.h"

uint uart_tx_init(PIO pio, uint pin, uint baudrate, uint data_bits, uint stop_bits, uint parity);
void uart_tx_write(uint32_t c);
void uart_tx_write_bytes(void *data, uint8_t length);
void uart_tx_remove(void);

#endif

================================================
FILE: board/project/pio/uart_tx.pio
================================================
/**
 * Copyright (c) 2025, Daniel Gorbea
 * All rights reserved.
 *
 * This source code is licensed under the MIT-style license found in the
 * LICENSE file in the root directory of this source tree. 
 */

.define PUBLIC UART_TX_CYCLES_PER_BIT 16  // we want here resolution to reduce division error when writing. more cycles less error

.program uart_tx  // 1 bit every 16 cycles
start:
    nop // set x n (0 to 31). Number of data bits
    pull block
    set pindirs 1 // take control of pin
    set pins 0 [16-2]  // start bit
bit_loop:
    out pins 1
    jmp x-- bit_loop [16-2]
    nop // set pins 1 [16*stop-1]. Stop bits (1-2)
    nop [16]
    set pindirs 0 // release pin

================================================
FILE: board/project/pio/ws2812.c
================================================
#include "ws2812.h"

#include "hardware/clocks.h"
#include "hardware/pio.h"
#include "pico/stdlib.h"

static uint sm_;
static PIO pio_;

static inline uint32_t urgb_u32(uint8_t r, uint8_t g, uint8_t b);

void ws2812_init(PIO pio, uint pin, float freq) {
    uint offset = pio_add_program(pio, &ws2812_program);
    pio_ = pio;
    sm_ = pio_claim_unused_sm(pio, true);
    pio_gpio_init(pio, pin);
    pio_sm_set_consecutive_pindirs(pio, sm_, pin, 1, true);
    pio_sm_config c = ws2812_program_get_default_config(offset);
    sm_config_set_sideset_pins(&c, pin);
    sm_config_set_out_shift(&c, false, true, 24);
    sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);

    int cycles_per_bit = ws2812_T1 + ws2812_T2 + ws2812_T3;
    float div = clock_get_hz(clk_sys) / (freq * cycles_per_bit);
    sm_config_set_clkdiv(&c, div);

    pio_sm_init(pio, sm_, offset, &c);
    pio_sm_set_enabled(pio, sm_, true);
}

void put_pixel_rgb(uint8_t r, uint8_t g, uint8_t b) { pio_sm_put_blocking(pio_, sm_, urgb_u32(r, g, b) << 8u); }

static inline uint32_t urgb_u32(uint8_t r, uint8_t g, uint8_t b) {
    return ((uint32_t)(r) << 8) | ((uint32_t)(g) << 16) | (uint32_t)(b);
}

================================================
FILE: board/project/pio/ws2812.h
================================================
#ifndef WS2812_H
#define WS2812_H

#include "ws2812.pio.h"

void ws2812_init(PIO pio, uint pin, float freq);
void put_pixel_rgb(uint8_t r, uint8_t g, uint8_t b);

#endif

================================================
FILE: board/project/pio/ws2812.pio
================================================
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;

.program ws2812
.side_set 1

.define public T1 2
.define public T2 5
.define public T3 3

.wrap_target
bitloop:
    out x, 1       side 0 [T3 - 1] ; Side-set still takes place when instruction stalls
    jmp !x do_zero side 1 [T1 - 1] ; Branch on the bit we shifted out. Positive pulse
do_one:
    jmp  bitloop   side 1 [T2 - 1] ; Continue driving high, for a long pulse
do_zero:
    nop            side 0 [T2 - 1] ; Or drive low, for a short pulse
.wrap




================================================
FILE: board/project/protocol/CMakeLists.txt
================================================
target_sources(${PROJECT_NAME} PRIVATE
    frsky_d.c
    hitec.c
    ibus.c
    jetiex.c
    multiplex.c
    sbus.c
    smartport.c
    srxl.c
    xbus.c
    srxl2.c
    crsf.c
    hott.c
    sanwa.c
    jr_dmss.c
    fport.c
    fbus.c
    ghst.c
    jetiex_sensor.c
)


================================================
FILE: board/project/protocol/crsf.c
================================================
#include "crsf.h"

#include <math.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>

#include "airspeed.h"
#include "bmp180.h"
#include "bmp280.h"
#include "config.h"
#include "current.h"
#include "esc_apd_f.h"
#include "esc_apd_hv.h"
#include "esc_castle.h"
#include "esc_hw3.h"
#include "esc_hw4.h"
#include "esc_hw5.h"
#include "esc_kontronik.h"
#include "esc_omp_m4.h"
#include "esc_pwm.h"
#include "esc_ztw.h"
#include "gps.h"
#include "ibus.h"
#include "ina3221.h"
#include "mpu6050.h"
#include "ms5611.h"
#include "ntc.h"
#include "pwm_out.h"
#include "smart_esc.h"
#include "uart.h"
#include "uart_pio.h"
#include "voltage.h"

#define CRSF_FRAMETYPE_GPS 0x02
#define CRSF_FRAMETYPE_VARIO 0x07
#define CRSF_FRAMETYPE_BATTERY_SENSOR 0x08
#define CRSF_FRAMETYPE_BARO_ALTITUDE 0x09
#define CRSF_FRAMETYPE_HEARTBEAT 0x0B
#define CRSF_FRAMETYPE_LINK_STATISTICS 0x14
#define CRSF_FRAMETYPE_RC_CHANNELS_PACKED 0x16
#define CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED 0x17
#define CRSF_FRAMETYPE_LINK_STATISTICS_RX 0x1C
#define CRSF_FRAMETYPE_LINK_STATISTICS_TX 0x1D
#define CRSF_FRAMETYPE_ATTITUDE 0x1E
#define CRSF_FRAMETYPE_FLIGHT_MODE 0x21
#define CRSF_FRAMETYPE_AIRSPEED 0x0A
#define CRSF_FRAMETYPE_RPM 0x0C
#define CRSF_FRAMETYPE_TEMP 0x0D
#define CRSF_FRAMETYPE_VOLTAGES 0x0E
#define CRSF_FRAMETYPE_GPS_TIME 0x03
#define CRSF_FRAMETYPE_GPS_EXTENDED 0x06

#define CRSF_TIMEOUT_US 1000

typedef enum crsf_sensor_type_t {
    TYPE_GPS,
    TYPE_VARIO,
    TYPE_BATERY,
    TYPE_BARO,
    TYPE_AIRSPEED,
    TYPE_RPM,
    TYPE_TEMP,
    TYPE_VOLTAGES,
    TYPE_GPS_TIME,
    TYPE_GPS_EXTENDED,
    TYPE_ATTITUDE,
    MAX_SENSORS
} crsf_sensor_type_t;

/*
CRSF frame has the structure:
<Device address> <Frame length> <Type> <Payload> <CRC>
Device address: (uint8_t)
Frame length:   length in  bytes including Type (uint8_t)
Type:           (uint8_t)
CRC:            (uint8_t), crc of <Type> and <Payload>
*/

typedef struct crsf_sensor_gps_formatted_t {
    int32_t latitude;      // degree / 10,000,000 big endian
    int32_t longitude;     // degree / 10,000,000 big endian
    uint16_t groundspeed;  // km/h / 10 big endian
    uint16_t heading;      // GPS heading, degree/100 big endian
    uint16_t altitude;     // meters, +1000m big endian
    uint8_t satellites;    // satellites
} __attribute__((packed)) crsf_sensor_gps_formatted_t;

typedef struct crsf_sensor_vario_formatted_t {
    int16_t vspeed;  // cm/s
} __attribute__((packed)) crsf_sensor_vario_formatted_t;

typedef struct crsf_sensor_baro_formatted_t {
    uint16_t altitude;
    int16_t vspeed;  // cm/s
} __attribute__((packed)) crsf_sensor_baro_formatted_t;

typedef struct crsf_sensor_battery_formatted_t {
    uint16_t voltage;        // V * 10 big endian
    uint16_t current;        // A * 10 big endian
    uint32_t capacity : 24;  // used capacity mah big endian
    uint8_t remaining;       // %
} __attribute__((packed)) crsf_sensor_battery_formatted_t;

typedef struct crsf_sensor_airspeed_formatted_t {
    uint16_t speed;  // V * 10 big endian
} __attribute__((packed)) crsf_sensor_airspeed_formatted_t;

typedef struct crsf_sensor_rpm_formatted_t {
    uint8_t source;
    uint32_t rpm : 24;
} __attribute__((packed)) crsf_sensor_rpm_formatted_t;

typedef struct crsf_sensor_temp_formatted_t {
    uint8_t source;
    int16_t temp;
} __attribute__((packed)) crsf_sensor_temp_formatted_t;

typedef struct crsf_sensor_voltages_formatted_t {
    uint8_t source;
    uint16_t voltage;
} __attribute__((packed)) crsf_sensor_voltages_formatted_t;

typedef struct crsf_sensor_gps_time_formatted_t {
    uint16_t year;
    uint8_t month;
    uint8_t day;
    uint8_t hour;
    uint8_t minute;
    uint8_t second;
    uint16_t millisecond;
} __attribute__((packed)) crsf_sensor_gps_time_formatted_t;

typedef struct crsf_sensor_gps_extended_formatted_t {
    uint8_t fix_type;       // Current GPS fix quality
    int16_t n_speed;        // Northward (north = positive) Speed [cm/sec]
    int16_t e_speed;        // Eastward (east = positive) Speed [cm/sec]
    int16_t v_speed;        // Vertical (up = positive) Speed [cm/sec]
    int16_t h_speed_acc;    // Horizontal Speed accuracy cm/sec
    int16_t track_acc;      // Heading accuracy in degrees scaled with 1e-1 degrees times 10)
    int16_t alt_ellipsoid;  // Meters Height above GPS Ellipsoid (not MSL)
    int16_t h_acc;          // horizontal accuracy in cm
    int16_t v_acc;          // vertical accuracy in cm
    uint8_t reserved;
    uint8_t hDOP;  // Horizontal dilution of precision,Dimensionless in nits of.1.
    uint8_t vDOP;  // vertical dilution of precision, Dimensionless in nits of .1.
} __attribute__((packed)) crsf_sensor_gps_extended_formatted_t;

typedef struct crsf_sensor_gps_t {
    float *latitude;     // degree / 10,000,000 big endian
    float *longitude;    // degree / 10,000,000 big endian
    float *groundspeed;  // km/h / 10 big endian
    float *heading;      // GPS heading, degree/100 big endian
    float *altitude;     // meters, +1000m big endian
    float *satellites;   // satellites
} crsf_sensor_gps_t;

typedef struct crsf_sensor_attitude_formatted_t {
    int16_t pitch;  // angle ( rad / 10000 )
    int16_t roll;   // angle ( rad / 10000 )
    int16_t yaw;    // angle ( rad / 10000 )
} __attribute__((packed)) crsf_sensor_attitude_formatted_t;

typedef struct crsf_sensor_vario_t {
    float *vspeed;  // cm/s
} crsf_sensor_vario_t;

typedef struct crsf_sensor_baro_t {
    float *altitude;
    float *vspeed;  // cm/s
} crsf_sensor_baro_t;

typedef struct crsf_sensor_battery_t {
    float *voltage;    // V * 10 big endian
    float *current;    // A * 10 big endian
    float *capacity;   // used capacity mah big endian
    float *remaining;  // %
} crsf_sensor_battery_t;

typedef struct crsf_sensor_airspeed_t {
    float *speed;  // km/h * 10 big endian
} crsf_sensor_airspeed_t;

typedef struct crsf_sensor_rpm_t {
    float *rpm;
} crsf_sensor_rpm_t;

typedef struct crsf_sensor_temp_t {
    uint8_t temperature_count;
    float *temperature[5];  // V * 10 big endian
} crsf_sensor_temp_t;

typedef struct crsf_sensor_voltages_t {
    bool is_cell_average;
    uint8_t *cell_count;
    float *cell[18];
    uint8_t voltage_count;
    float *voltage[10];
} crsf_sensor_voltages_t;

typedef struct crsf_sensor_gps_time_t {
    float *date;
    float *time;
} crsf_sensor_gps_time_t;

typedef struct crsf_sensor_gps_extended_t {
    float *fix;
    float *n_speed;
    float *e_speed;
    float *v_speed;
    float *h_speed_acc;
    float *track_acc;
    float *alt_ellipsoid;
    float *h_acc;
    float *v_acc;
    float *hdop;
    float *vdop;
} crsf_sensor_gps_extended_t;

typedef struct crsf_sensor_attitude_t {
    float *pitch;
    float *roll;
    float *yaw;
} crsf_sensor_attitude_t;

typedef struct crsf_sensors_t {
    bool enabled_sensors[MAX_SENSORS];
    crsf_sensor_gps_t gps;
    crsf_sensor_vario_t vario;
    crsf_sensor_battery_t battery;
    crsf_sensor_baro_t baro;
    crsf_sensor_airspeed_t airspeed;
    crsf_sensor_rpm_t rpm;
    crsf_sensor_temp_t temperature;
    crsf_sensor_voltages_t voltages;
    crsf_sensor_gps_time_t gps_time;
    crsf_sensor_gps_extended_t gps_extended;
    crsf_sensor_attitude_t attitude;
} crsf_sensors_t;

static uint8_t format_sensor(crsf_sensors_t *sensors, uint8_t type, uint8_t *buffer);
static void send_packet(crsf_sensors_t *sensors);
static uint8_t get_crc(const uint8_t *ptr, uint32_t len);
static uint8_t crc8(uint8_t crc, unsigned char a);
static void set_config(crsf_sensors_t *sensors);
static inline uint sensor_count(crsf_sensors_t *sensors);

void crsf_task(void *parameters) {
    crsf_sensors_t sensors = {0};
    set_config(&sensors);
    context.led_cycle_duration = 6;
    context.led_cycles = 1;
    uart0_begin(416666L, UART_RECEIVER_TX, UART_RECEIVER_RX, CRSF_TIMEOUT_US, 8, 1, UART_PARITY_NONE, false, false);
    debug("\nCRSF init");
    while (1) {
        vTaskDelay(20 / portTICK_PERIOD_MS);
        send_packet(&sensors);
    }
}

static uint8_t format_sensor(crsf_sensors_t *sensors, uint8_t type, uint8_t *buffer) {
    // Packet format: [sync] [len (from type)] [type] [payload] [crc8 from type]
    uint len = 0;
    buffer[0] = 0xC8;
    switch (type) {
        case TYPE_GPS: {
            buffer[1] = sizeof(crsf_sensor_gps_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_GPS;
            crsf_sensor_gps_formatted_t sensor = {0};
            if (sensors->gps.latitude) sensor.latitude = swap_32((int32_t)(*sensors->gps.latitude * 10000000L));
            if (sensors->gps.longitude) sensor.longitude = swap_32((int32_t)(*sensors->gps.longitude * 10000000L));
            if (sensors->gps.groundspeed)
                sensor.groundspeed = swap_16((uint16_t)(fabs(*sensors->gps.groundspeed * 10)));
            if (sensors->gps.satellites) sensor.satellites = *sensors->gps.satellites;
            if (sensors->gps.heading) sensor.heading = swap_16((uint16_t)(*sensors->gps.heading * 100));
            if (sensors->gps.altitude) {
                float altitude = *sensors->gps.altitude + 1000;
                if (altitude < 0) altitude = 0;
                if (altitude > 65535) altitude = 65535;
                sensor.altitude = swap_16((uint16_t)altitude);
            }
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_gps_formatted_t));
            buffer[3 + sizeof(crsf_sensor_gps_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_gps_formatted_t) + 1);
            len = sizeof(crsf_sensor_gps_formatted_t) + 4;
            break;
        }
        case TYPE_VARIO: {
            buffer[1] = sizeof(crsf_sensor_vario_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_VARIO;
            crsf_sensor_vario_formatted_t sensor = {0};
            if (sensors->vario.vspeed) sensor.vspeed = swap_16((int16_t)(*sensors->vario.vspeed * 100));
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_vario_formatted_t));
            buffer[3 + sizeof(crsf_sensor_vario_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_vario_formatted_t) + 1);
            len = sizeof(crsf_sensor_vario_formatted_t) + 4;
            break;
        }
        case TYPE_BATERY: {
            buffer[1] = sizeof(crsf_sensor_battery_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_BATTERY_SENSOR;
            crsf_sensor_battery_formatted_t sensor = {0};
            if (sensors->battery.voltage) sensor.voltage = swap_16((uint16_t)(*sensors->battery.voltage * 10));
            if (sensors->battery.current) sensor.current = swap_16((uint16_t)(*sensors->battery.current * 10));
            if (sensors->battery.capacity) sensor.capacity = swap_24((uint32_t)*sensors->battery.capacity);
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_battery_formatted_t));
            buffer[3 + sizeof(crsf_sensor_battery_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_battery_formatted_t) + 1);
            len = sizeof(crsf_sensor_battery_formatted_t) + 4;
            break;
        }
        case TYPE_BARO: {
            buffer[1] = sizeof(crsf_sensor_baro_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_BARO_ALTITUDE;
            crsf_sensor_baro_formatted_t sensor = {0};
            if (sensors->baro.vspeed) sensor.vspeed = swap_16((int16_t)(*sensors->baro.vspeed * 100));
            if (sensors->baro.altitude) {
                float altitude = *sensors->baro.altitude + 1000;
                if (altitude < 0) altitude = 0;
                if (altitude > 3276) altitude = 3276;
                sensor.altitude = swap_16((uint16_t)(altitude * 10));
            }
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_baro_formatted_t));
            buffer[3 + sizeof(crsf_sensor_baro_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_baro_formatted_t) + 1);
            len = sizeof(crsf_sensor_baro_formatted_t) + 4;
            break;
        }
        case TYPE_AIRSPEED: {
            buffer[1] = sizeof(crsf_sensor_airspeed_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_AIRSPEED;
            crsf_sensor_airspeed_formatted_t sensor = {0};
            if (sensors->airspeed.speed) sensor.speed = swap_16((int16_t)(*sensors->airspeed.speed * 10));
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_airspeed_formatted_t));
            buffer[3 + sizeof(crsf_sensor_airspeed_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_airspeed_formatted_t) + 1);
            len = sizeof(crsf_sensor_airspeed_formatted_t) + 4;
            break;
        }
        case TYPE_RPM: {
            buffer[1] = sizeof(crsf_sensor_rpm_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_RPM;
            crsf_sensor_rpm_formatted_t sensor = {0};
            if (sensors->rpm.rpm) sensor.rpm = swap_24((int32_t)(*sensors->rpm.rpm));
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_rpm_formatted_t));
            buffer[3 + sizeof(crsf_sensor_rpm_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_rpm_formatted_t) + 1);
            len = sizeof(crsf_sensor_rpm_formatted_t) + 4;
            break;
        }
        case TYPE_TEMP: {
            static uint8_t count = 0;
            buffer[1] = sizeof(crsf_sensor_temp_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_TEMP;
            crsf_sensor_temp_formatted_t sensor = {0};
            sensor.source = count;
            if (sensors->temperature.temperature[count])
                sensor.temp = swap_16((int16_t)(*sensors->temperature.temperature[count] * 10));
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_temp_formatted_t));
            buffer[3 + sizeof(crsf_sensor_temp_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_temp_formatted_t) + 1);
            len = sizeof(crsf_sensor_temp_formatted_t) + 4;
            count++;
            if (count >= sensors->temperature.temperature_count) count = 0;
            break;
        }
        case TYPE_VOLTAGES: {
            static uint8_t cell_index = 0;
            static uint8_t voltage_index = 0;
            static bool send_cell = true;
            if (*sensors->voltages.cell_count == 0) send_cell = false;
            buffer[2] = CRSF_FRAMETYPE_VOLTAGES;
            crsf_sensor_voltages_formatted_t sensor = {0};
            buffer[1] = sizeof(crsf_sensor_voltages_formatted_t) + 2;
            if (send_cell && *sensors->voltages.cell_count > 0) {
                sensor.source = cell_index;
                if (sensors->voltages.is_cell_average && sensors->voltages.cell[0]) {
                    sensor.voltage = swap_16((uint16_t)(*sensors->voltages.cell[0] * 1000));
                } else if (sensors->voltages.cell[cell_index]) {
                    sensor.voltage = swap_16((uint16_t)(*sensors->voltages.cell[cell_index] * 1000));
                }

                memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_voltages_formatted_t));
                buffer[3 + sizeof(crsf_sensor_voltages_formatted_t)] =
                    get_crc(&buffer[2], sizeof(crsf_sensor_voltages_formatted_t) + 1);
                len = sizeof(crsf_sensor_voltages_formatted_t) + 4;
                buffer[1] = sizeof(crsf_sensor_voltages_formatted_t) + 2;

                cell_index++;
                if (cell_index >= *sensors->voltages.cell_count) {
                    cell_index = 0;
                    if (sensors->voltages.voltage_count) send_cell = false;
                }
            } else if (sensors->voltages.voltage_count > 0) {
                sensor.source = voltage_index + 128;
                sensor.voltage = swap_16((uint16_t)(*sensors->voltages.voltage[voltage_index] * 1000));

                memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_voltages_formatted_t));
                buffer[3 + sizeof(crsf_sensor_voltages_formatted_t)] =
                    get_crc(&buffer[2], sizeof(crsf_sensor_voltages_formatted_t) + 1);
                len = sizeof(crsf_sensor_voltages_formatted_t) + 4;
                buffer[1] = sizeof(crsf_sensor_voltages_formatted_t) + 2;

                voltage_index++;
                if (voltage_index >= sensors->voltages.voltage_count) {
                    voltage_index = 0;
                    send_cell = true;
                    if (*sensors->voltages.cell_count) send_cell = true;
                }
            }
            break;
        }
        case TYPE_GPS_TIME: {
            buffer[1] = sizeof(crsf_sensor_gps_time_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_GPS_TIME;
            crsf_sensor_gps_time_formatted_t sensor = {0};
            uint16_t year = *sensors->gps_time.date / 10000 + 2000;
            sensor.year = swap_16(year);
            sensor.month = ((uint)*sensors->gps_time.date - (year - 2000) * 10000) / 100;
            sensor.day = (uint)*sensors->gps_time.date - (year - 2000) * 10000 - sensor.month * 100;
            sensor.hour = (uint)*sensors->gps_time.time / 10000;
            sensor.minute = ((uint)*sensors->gps_time.time - sensor.hour * 10000) / 100;
            sensor.second = ((uint)*sensors->gps_time.time - sensor.hour * 10000 - sensor.minute * 100);
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_gps_time_formatted_t));
            buffer[3 + sizeof(crsf_sensor_gps_time_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_gps_time_formatted_t) + 1);
            len = sizeof(crsf_sensor_gps_time_formatted_t) + 4;
            break;
        }
        case TYPE_GPS_EXTENDED: {
            buffer[1] = sizeof(crsf_sensor_gps_extended_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_GPS_EXTENDED;
            crsf_sensor_gps_extended_formatted_t sensor = {0};
            sensor.fix_type = *sensors->gps_extended.fix;
            sensor.n_speed = *sensors->gps_extended.n_speed / 10;
            sensor.e_speed = *sensors->gps_extended.e_speed / 10;
            sensor.v_speed = *sensors->gps_extended.v_speed / 10;
            sensor.h_speed_acc = *sensors->gps_extended.h_speed_acc / 10;
            sensor.track_acc = *sensors->gps_extended.track_acc / 10;
            sensor.alt_ellipsoid = *sensors->gps_extended.alt_ellipsoid / 10;
            sensor.hDOP = *sensors->gps_extended.hdop * 10;
            sensor.vDOP = *sensors->gps_extended.vdop * 10;
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_gps_extended_formatted_t));
            buffer[3 + sizeof(crsf_sensor_gps_extended_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_gps_extended_formatted_t) + 1);
            len = sizeof(crsf_sensor_gps_extended_formatted_t) + 4;
            break;
        }
        case TYPE_ATTITUDE: {
            buffer[1] = sizeof(crsf_sensor_attitude_formatted_t) + 2;
            buffer[2] = CRSF_FRAMETYPE_ATTITUDE;
            crsf_sensor_attitude_formatted_t sensor = {0};
            if (sensors->attitude.pitch) sensor.pitch = swap_16((int16_t)(*sensors->attitude.pitch * 10000));
            if (sensors->attitude.roll) sensor.roll = swap_16((int16_t)(*sensors->attitude.roll * 10000));
            if (sensors->attitude.yaw) sensor.yaw = swap_16((int16_t)(*sensors->attitude.yaw * 10000));
            memcpy(&buffer[3], &sensor, sizeof(crsf_sensor_attitude_formatted_t));
            buffer[3 + sizeof(crsf_sensor_attitude_formatted_t)] =
                get_crc(&buffer[2], sizeof(crsf_sensor_attitude_formatted_t) + 1);
            len = sizeof(crsf_sensor_attitude_formatted_t) + 4;
            break;
        }
    }
    return len;
}

static inline uint sensor_count(crsf_sensors_t *sensors) {
    uint count = 0;
    for (uint i = 0; i < MAX_SENSORS; i++)
        if (sensors->enabled_sensors[i]) count++;
    return count;
}

static void send_packet(crsf_sensors_t *sensors) {
    if (!sensor_count(sensors)) return;
    static uint type = 0;
    uint8_t buffer[64] = {0};
    while (!sensors->enabled_sensors[type % MAX_SENSORS]) type++;
    uint len = format_sensor(sensors, type % MAX_SENSORS, buffer);
    uart0_write_bytes(buffer, len);
    type++;
    debug("\nCRSF (%u) > ", uxTaskGetStackHighWaterMark(NULL));
    debug_buffer(buffer, len, "0x%X ");

    // blink led
    vTaskResume(context.led_task_handle);
}

static uint8_t get_crc(const uint8_t *ptr, uint32_t len) {
    uint8_t crc = 0;
    for (uint32_t i = 0; i < len; i++) {
        crc = crc8(crc, *ptr++);
    }
    return crc;
}

static uint8_t crc8(uint8_t crc, unsigned char a) {
    crc ^= a;
    for (int ii = 0; ii < 8; ++ii) {
        if (crc & 0x80) {
            crc = (crc << 1) ^ 0xD5;
        } else {
            crc = crc << 1;
        }
    }
    return crc;
}

static void set_config(crsf_sensors_t *sensors) {
    config_t *config = config_read();
    TaskHandle_t task_handle;
    float *baro_temp = NULL, *baro_pressure = NULL;
    if (config->esc_protocol == ESC_PWM) {
        esc_pwm_parameters_t parameter = {config->rpm_multiplier, config->alpha_rpm, malloc(sizeof(float))};
        xTaskCreate(esc_pwm_task, "esc_pwm_task", STACK_ESC_PWM, (void *)&parameter, 2, &task_handle);

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_HW3) {
        esc_hw3_parameters_t parameter = {config->rpm_multiplier, config->alpha_rpm, malloc(sizeof(float))};
        xTaskCreate(esc_hw3_task, "esc_hw3_task", STACK_ESC_HW3, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_HW4) {
        esc_hw4_parameters_t parameter = {config->rpm_multiplier,
                                          config->enable_pwm_out,
                                          config->enable_esc_hw4_init_delay,
                                          config->alpha_rpm,
                                          config->alpha_voltage,
                                          config->alpha_current,
                                          config->alpha_temperature,
                                          config->esc_hw4_voltage_multiplier,
                                          config->esc_hw4_current_multiplier,
                                          config->esc_hw4_current_thresold,
                                          config->esc_hw4_current_max,
                                          config->esc_hw4_is_manual_offset,
                                          config->esc_hw4_auto_detect,
                                          config->esc_hw4_offset,
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(float)),
                                          malloc(sizeof(uint8_t))};
        xTaskCreate(esc_hw4_task, "esc_hw4_task", STACK_ESC_HW4, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;
        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
        if (config->enable_pwm_out) {
            xTaskCreate(pwm_out_task, "pwm_out", STACK_PWM_OUT, (void *)parameter.rpm, 2, &task_handle);
            context.pwm_out_task_handle = task_handle;
            ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
        }

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_fet;
        sensors->temperature.temperature_count++;

        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_bec;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;
    }
    if (config->esc_protocol == ESC_HW5) {
        esc_hw5_parameters_t parameter = {
            config->rpm_multiplier,    config->alpha_rpm,     config->alpha_voltage, config->alpha_current,
            config->alpha_temperature, malloc(sizeof(float)), malloc(sizeof(float)), malloc(sizeof(float)),
            malloc(sizeof(float)),     malloc(sizeof(float)), malloc(sizeof(float)), malloc(sizeof(float)),
            malloc(sizeof(float)),     malloc(sizeof(float)), malloc(sizeof(float)), malloc(sizeof(uint8_t))};
        xTaskCreate(esc_hw5_task, "esc_hw5_task", STACK_ESC_HW5, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;
        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_fet;
        sensors->temperature.temperature_count++;

        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_bec;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;

        sensors->voltages.voltage[sensors->voltages.voltage_count] = parameter.voltage_bec;
        sensors->voltages.voltage_count++;
    }
    if (config->esc_protocol == ESC_CASTLE) {
        esc_castle_parameters_t parameter = {config->rpm_multiplier, config->alpha_rpm,         config->alpha_voltage,
                                             config->alpha_current,  config->alpha_temperature, malloc(sizeof(float)),
                                             malloc(sizeof(float)),  malloc(sizeof(float)),     malloc(sizeof(float)),
                                             malloc(sizeof(float)),  malloc(sizeof(float)),     malloc(sizeof(float)),
                                             malloc(sizeof(float)),  malloc(sizeof(float)),     malloc(sizeof(float)),
                                             malloc(sizeof(float)),  malloc(sizeof(uint8_t))};
        xTaskCreate(esc_castle_task, "esc_castle_task", STACK_ESC_CASTLE, (void *)&parameter, 2, &task_handle);

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;

        sensors->voltages.voltage[sensors->voltages.voltage_count] = parameter.voltage_bec;
        sensors->voltages.voltage_count++;
        sensors->voltages.voltage[sensors->voltages.voltage_count] = parameter.ripple_voltage;
        sensors->voltages.voltage_count++;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_KONTRONIK) {
        esc_kontronik_parameters_t parameter = {
            config->rpm_multiplier,    config->alpha_rpm,     config->alpha_voltage,  config->alpha_current,
            config->alpha_temperature, malloc(sizeof(float)), malloc(sizeof(float)),  malloc(sizeof(float)),
            malloc(sizeof(float)),     malloc(sizeof(float)), malloc(sizeof(float)),  malloc(sizeof(float)),
            malloc(sizeof(float)),     malloc(sizeof(float)), malloc(sizeof(uint8_t))};
        xTaskCreate(esc_kontronik_task, "esc_kontronik_task", STACK_ESC_KONTRONIK, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_fet;
        sensors->temperature.temperature_count++;

        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_bec;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;

        sensors->voltages.voltage[sensors->voltages.voltage_count] = parameter.voltage_bec;
        sensors->voltages.voltage_count++;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_APD_F) {
        esc_apd_f_parameters_t parameter = {config->rpm_multiplier, config->alpha_rpm,         config->alpha_voltage,
                                            config->alpha_current,  config->alpha_temperature, malloc(sizeof(float)),
                                            malloc(sizeof(float)),  malloc(sizeof(float)),     malloc(sizeof(float)),
                                            malloc(sizeof(float)),  malloc(sizeof(float)),     malloc(sizeof(uint8_t))};
        xTaskCreate(esc_apd_f_task, "esc_apd_f_task", STACK_ESC_APD_F, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_APD_HV) {
        esc_apd_hv_parameters_t parameter = {
            config->rpm_multiplier,    config->alpha_rpm,     config->alpha_voltage, config->alpha_current,
            config->alpha_temperature, malloc(sizeof(float)), malloc(sizeof(float)), malloc(sizeof(float)),
            malloc(sizeof(float)),     malloc(sizeof(float)), malloc(sizeof(float)), malloc(sizeof(uint8_t))};
        xTaskCreate(esc_apd_hv_task, "esc_apd_hv_task", STACK_ESC_APD_HV, (void *)&parameter, 2, &task_handle);
        context.uart1_notify_task_handle = task_handle;

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature;
        sensors->temperature.temperature_count++;

        sensors->enabled_sensors[TYPE_VOLTAGES] = true;
        sensors->voltages.is_cell_average = true;
        sensors->voltages.cell_count = parameter.cell_count;
        sensors->voltages.cell[0] = parameter.cell_voltage;

        ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
    }
    if (config->esc_protocol == ESC_SMART) {
        smart_esc_parameters_t parameter;
        parameter.rpm_multiplier = config->rpm_multiplier;
        parameter.alpha_rpm = config->alpha_rpm;
        parameter.alpha_voltage = config->alpha_voltage;
        parameter.alpha_current = config->alpha_current;
        parameter.alpha_temperature = config->alpha_temperature;
        parameter.rpm = malloc(sizeof(float));
        parameter.voltage = malloc(sizeof(float));
        parameter.current = malloc(sizeof(float));
        parameter.temperature_fet = malloc(sizeof(float));
        parameter.temperature_bec = malloc(sizeof(float));
        parameter.voltage_bec = malloc(sizeof(float));
        parameter.current_bec = malloc(sizeof(float));
        parameter.temperature_bat = malloc(sizeof(float));
        parameter.current_bat = malloc(sizeof(float));
        parameter.consumption = malloc(sizeof(float));
        for (uint i = 0; i < 18; i++) parameter.cell[i] = malloc(sizeof(float));
        parameter.cells = malloc(sizeof(uint8_t));
        parameter.cycles = malloc(sizeof(uint16_t));
        xTaskCreate(smart_esc_task, "smart_esc_task", STACK_SMART_ESC, (void *)&parameter, 4, &task_handle);
        context.uart1_notify_task_handle = task_handle;

        sensors->enabled_sensors[TYPE_BATERY] = true;
        sensors->battery.voltage = parameter.voltage;
        sensors->battery.current = parameter.current;
        sensors->battery.capacity = parameter.consumption;

        sensors->enabled_sensors[TYPE_RPM] = true;
        sensors->rpm.rpm = parameter.rpm;

        sensors->enabled_sensors[TYPE_TEMP] = true;
        sensors->temperature.temperature[sensors->temperature.temperature_count] = parameter.temperature_fet;
        sensor
Download .txt
gitextract_7zabuz1p/

├── .clang-format
├── .gitattributes
├── .github/
│   ├── copilot-instructions.md
│   └── workflows/
│       ├── build_release.yaml
│       ├── ci_firmware.yaml
│       ├── ci_msrc_link.yaml
│       ├── dev_firmware.yaml
│       └── dev_msrc_link.yaml
├── .gitignore
├── .gitmodules
├── .vscode/
│   ├── c_cpp_properties.json
│   ├── launch.json
│   └── settings.json
├── LICENSE
├── README.md
├── board/
│   ├── CMakeLists.txt
│   ├── freertos/
│   │   ├── CMakeLists.txt
│   │   └── FreeRTOSConfig.h
│   ├── pico_sdk_import.cmake
│   └── project/
│       ├── CMakeLists.txt
│       ├── common.c
│       ├── common.h
│       ├── config.c
│       ├── config.h
│       ├── constants.h
│       ├── dbg_rb.c
│       ├── dbg_rb.h
│       ├── dbg_task.c
│       ├── dbg_task.h
│       ├── led.c
│       ├── led.h
│       ├── main.c
│       ├── pio/
│       │   ├── CMakeLists.txt
│       │   ├── capture_edge.c
│       │   ├── capture_edge.h
│       │   ├── capture_edge.pio
│       │   ├── castle_link.c
│       │   ├── castle_link.h
│       │   ├── castle_link.pio
│       │   ├── i2c_multi.c
│       │   ├── i2c_multi.h
│       │   ├── i2c_multi.pio
│       │   ├── uart_rx.c
│       │   ├── uart_rx.h
│       │   ├── uart_rx.pio
│       │   ├── uart_tx.c
│       │   ├── uart_tx.h
│       │   ├── uart_tx.pio
│       │   ├── ws2812.c
│       │   ├── ws2812.h
│       │   └── ws2812.pio
│       ├── protocol/
│       │   ├── CMakeLists.txt
│       │   ├── crsf.c
│       │   ├── crsf.h
│       │   ├── fbus.c
│       │   ├── fbus.h
│       │   ├── fport.c
│       │   ├── fport.h
│       │   ├── frsky_d.c
│       │   ├── frsky_d.h
│       │   ├── ghst.c
│       │   ├── ghst.h
│       │   ├── hitec.c
│       │   ├── hitec.h
│       │   ├── hott.c
│       │   ├── hott.h
│       │   ├── ibus.c
│       │   ├── ibus.h
│       │   ├── jetiex.c
│       │   ├── jetiex.h
│       │   ├── jetiex_sensor.c
│       │   ├── jetiex_sensor.h
│       │   ├── jr_dmss.c
│       │   ├── jr_dmss.h
│       │   ├── multiplex.c
│       │   ├── multiplex.h
│       │   ├── sanwa.c
│       │   ├── sanwa.h
│       │   ├── sbus.c
│       │   ├── sbus.h
│       │   ├── smartport.c
│       │   ├── smartport.h
│       │   ├── srxl.c
│       │   ├── srxl.h
│       │   ├── srxl2.c
│       │   ├── srxl2.h
│       │   ├── xbus.c
│       │   └── xbus.h
│       ├── sensor/
│       │   ├── CMakeLists.txt
│       │   ├── airspeed.c
│       │   ├── airspeed.h
│       │   ├── auto_offset.c
│       │   ├── auto_offset.h
│       │   ├── bmp180.c
│       │   ├── bmp180.h
│       │   ├── bmp280.c
│       │   ├── bmp280.h
│       │   ├── cell_count.c
│       │   ├── cell_count.h
│       │   ├── current.c
│       │   ├── current.h
│       │   ├── distance.c
│       │   ├── distance.h
│       │   ├── esc_apd_f.c
│       │   ├── esc_apd_f.h
│       │   ├── esc_apd_hv.c
│       │   ├── esc_apd_hv.h
│       │   ├── esc_castle.c
│       │   ├── esc_castle.h
│       │   ├── esc_hw3.c
│       │   ├── esc_hw3.h
│       │   ├── esc_hw4.c
│       │   ├── esc_hw4.h
│       │   ├── esc_hw5.c
│       │   ├── esc_hw5.h
│       │   ├── esc_kontronik.c
│       │   ├── esc_kontronik.h
│       │   ├── esc_omp_m4.c
│       │   ├── esc_omp_m4.h
│       │   ├── esc_openyge.c
│       │   ├── esc_openyge.h
│       │   ├── esc_pwm.c
│       │   ├── esc_pwm.h
│       │   ├── esc_ztw.c
│       │   ├── esc_ztw.h
│       │   ├── fuel_meter.c
│       │   ├── fuel_meter.h
│       │   ├── gpio.c
│       │   ├── gpio.h
│       │   ├── gps.c
│       │   ├── gps.h
│       │   ├── ina3221.c
│       │   ├── ina3221.h
│       │   ├── mpu6050.c
│       │   ├── mpu6050.h
│       │   ├── ms5611.c
│       │   ├── ms5611.h
│       │   ├── ntc.c
│       │   ├── ntc.h
│       │   ├── pwm_out.c
│       │   ├── pwm_out.h
│       │   ├── smart_esc.c
│       │   ├── smart_esc.h
│       │   ├── voltage.c
│       │   ├── voltage.h
│       │   ├── vspeed.c
│       │   ├── vspeed.h
│       │   ├── xgzp68xxd.c
│       │   └── xgzp68xxd.h
│       ├── serial_monitor.c
│       ├── serial_monitor.h
│       ├── sim_rx.c
│       ├── sim_rx.h
│       ├── uart.c
│       ├── uart.h
│       ├── uart_pio.c
│       ├── uart_pio.h
│       ├── usb.c
│       └── usb.h
├── case/
│   ├── MSRC_case_zero-Lower case.stl
│   ├── MSRC_case_zero-Upper case.stl
│   ├── MSRC_case_zero.3mf
│   ├── MSRC_case_zero.FCStd
│   └── MSRC_case_zero_PLA_1h27m.gcode
├── include/
│   └── shared.h
├── lua/
│   └── MSRC.lua
├── msrc_gui/
│   ├── appdir/
│   │   └── msrc.desktop
│   ├── circuitdialog.cpp
│   ├── circuitdialog.h
│   ├── circuitdialog.ui
│   ├── main.cpp
│   ├── mainwindow.cpp
│   ├── mainwindow.h
│   ├── mainwindow.ui
│   ├── msrc_gui.pro
│   └── resources.qrc
└── msrc_gui_web/
    ├── README.md
    ├── css/
    │   └── style.css
    ├── index.html
    ├── js/
    │   ├── app.js
    │   ├── circuit.js
    │   ├── config_struct.js
    │   ├── serial.js
    │   ├── ui.js
    │   └── version.js
    ├── manifest.json
    ├── sw.js
    └── test/
        ├── layout_test.html
        └── verify_layout.js
Download .txt
SYMBOL INDEX (643 symbols across 115 files)

FILE: board/project/common.c
  function get_average (line 11) | float get_average(float alpha, float prev_value, float new_value) {
  function get_consumption (line 19) | float get_consumption(float current, uint16_t current_max, uint32_t *tim...
  function voltage_read (line 32) | float voltage_read(uint8_t adc_num) {
  function get_altitude (line 37) | float get_altitude(float pressure, float temperature, float pressure_ini...
  function get_vspeed (line 42) | void get_vspeed(float *vspeed, float altitude, uint interval) {
  function get_vspeed_gps (line 53) | void get_vspeed_gps(float *vspeed, float altitude, uint interval) {

FILE: board/project/common.h
  type context_t (line 54) | typedef struct context_t {

FILE: board/project/config.c
  function config_t (line 137) | config_t *config_read() {
  function config_write (line 157) | void config_write(config_t *config) {
  function config_get (line 166) | void config_get(config_t *config) {
  function config_forze_write (line 171) | void config_forze_write() {

FILE: board/project/dbg_rb.c
  function rb_next (line 8) | static inline size_t rb_next(size_t idx) {
  function dbg_rb_init (line 12) | bool dbg_rb_init(uint8_t *storage, size_t capacity) {
  function dbg_rb_available (line 21) | size_t dbg_rb_available(void) {
  function dbg_rb_free (line 28) | size_t dbg_rb_free(void) {
  function dbg_rb_push (line 33) | size_t dbg_rb_push(const uint8_t *data, size_t len) {
  function dbg_rb_pop (line 47) | size_t dbg_rb_pop(uint8_t *out, size_t len) {

FILE: board/project/dbg_task.c
  function dbg_notify (line 32) | static void dbg_notify(void) {
  function dbg_task_init (line 38) | void dbg_task_init(void) {
  function dbg_task_fn (line 46) | static void dbg_task_fn(void *arg) {
  function dbg_task_start (line 68) | void dbg_task_start(unsigned stack_words, unsigned priority) {
  function dbg_write (line 83) | int dbg_write(const char *fmt, ...) {
  function dbg_write_buffer (line 106) | void dbg_write_buffer(const uint8_t *buffer, size_t length, const char *...

FILE: board/project/led.c
  function led_task (line 6) | void led_task() {

FILE: board/project/main.c
  function vApplicationStackOverflowHook (line 30) | void vApplicationStackOverflowHook(TaskHandle_t xTask, char *pcTaskName) {
  function main (line 36) | int main() {

FILE: board/project/pio/capture_edge.c
  function capture_edge_init (line 31) | void capture_edge_init(PIO pio, uint pin_base, uint pin_count, float clk...
  function capture_edge_set_handler (line 135) | void capture_edge_set_handler(uint pin, capture_handler_t handler) {
  function capture_edge_remove (line 141) | void capture_edge_remove(void) {
  function handler_pio (line 153) | static inline void handler_pio(void) {
  function edge_type_t (line 165) | static inline edge_type_t get_captured_edge(uint pin, uint pins, uint pr...
  function uint (line 171) | static inline uint bit_value(uint pos) { return 1 << pos; }

FILE: board/project/pio/capture_edge.h
  type edge_type_t (line 21) | typedef enum edge_type_t { EDGE_NONE, EDGE_FALL, EDGE_RISE } edge_type_t;

FILE: board/project/pio/castle_link.c
  function castle_link_init (line 15) | void castle_link_init(PIO pio, uint pin, uint irq) {
  function castle_link_set_handler (line 48) | void castle_link_set_handler(castle_link_handler_t handler) { handler_ =...
  function castle_link_remove (line 50) | void castle_link_remove() {
  function handler_pio (line 58) | static inline void handler_pio() {

FILE: board/project/pio/castle_link.h
  type castle_link_telemetry_t (line 23) | typedef struct castle_link_telemetry_t {

FILE: board/project/pio/i2c_multi.c
  function i2c_multi_init (line 27) | void i2c_multi_init(PIO pio, uint pin) {
  function i2c_multi_set_write_buffer (line 70) | void i2c_multi_set_write_buffer(uint8_t *buffer) {
  function i2c_multi_set_receive_handler (line 75) | void i2c_multi_set_receive_handler(i2c_multi_receive_handler_t handler) ...
  function i2c_multi_set_request_handler (line 77) | void i2c_multi_set_request_handler(i2c_multi_request_handler_t handler) ...
  function i2c_multi_set_stop_handler (line 79) | void i2c_multi_set_stop_handler(i2c_multi_stop_handler_t handler) { stop...
  function i2c_multi_enable_address (line 81) | void i2c_multi_enable_address(uint8_t address) { i2c_multi->address[addr...
  function i2c_multi_disable_address (line 83) | void i2c_multi_disable_address(uint8_t address) { i2c_multi->address[add...
  function i2c_multi_enable_all_addresses (line 85) | void i2c_multi_enable_all_addresses() {
  function i2c_multi_disable_all_addresses (line 92) | void i2c_multi_disable_all_addresses() {
  function i2c_multi_is_address_enabled (line 99) | bool i2c_multi_is_address_enabled(uint8_t address) { return i2c_multi->a...
  function i2c_multi_disable (line 101) | void i2c_multi_disable() {
  function i2c_multi_restart (line 115) | void i2c_multi_restart() {
  function i2c_multi_remove (line 131) | void i2c_multi_remove() {
  function i2c_multi_fixed_length (line 151) | void i2c_multi_fixed_length(int16_t length) { i2c_multi->length = length; }
  function start_condition_program_init (line 153) | static inline void start_condition_program_init(PIO pio, uint sm, uint o...
  function stop_condition_program_init (line 162) | static inline void stop_condition_program_init(PIO pio, uint sm, uint of...
  function read_byte_program_init (line 173) | static inline void read_byte_program_init(PIO pio, uint sm, uint offset,...
  function write_byte_program_init (line 186) | static inline void write_byte_program_init(PIO pio, uint sm, uint offset...
  function byte_handler_pio (line 200) | static inline void byte_handler_pio() {
  function stop_handler_pio (line 304) | static inline void stop_handler_pio() {
  function transpond_byte (line 319) | static inline uint8_t transpond_byte(uint8_t byte) {

FILE: board/project/pio/i2c_multi.h
  type i2c_multi_status_t (line 7) | typedef enum i2c_multi_status_t { I2C_IDLE, I2C_READ, I2C_WRITE } i2c_mu...
  type i2c_multi_t (line 13) | typedef struct i2c_multi_t {

FILE: board/project/pio/uart_rx.c
  function uint (line 14) | uint uart_rx_init(PIO pio, uint pin, uint baudrate, uint irq) {
  function uart_rx_set_handler (line 44) | void uart_rx_set_handler(uart_rx_handler_t handler) { handler_ = handler; }
  function uart_rx_remove (line 46) | void uart_rx_remove(void) {
  function handler_pio (line 52) | static inline void handler_pio(void) {

FILE: board/project/pio/uart_tx.c
  function uint (line 12) | uint uart_tx_init(PIO pio, uint pin, uint baudrate, uint data_bits, uint...
  function uart_tx_write (line 36) | void uart_tx_write(uint32_t c) {
  function uart_tx_write_bytes (line 50) | void uart_tx_write_bytes(void *data, uint8_t length) {
  function uart_tx_remove (line 66) | void uart_tx_remove(void) {

FILE: board/project/pio/ws2812.c
  function ws2812_init (line 12) | void ws2812_init(PIO pio, uint pin, float freq) {
  function put_pixel_rgb (line 31) | void put_pixel_rgb(uint8_t r, uint8_t g, uint8_t b) { pio_sm_put_blockin...
  function urgb_u32 (line 33) | static inline uint32_t urgb_u32(uint8_t r, uint8_t g, uint8_t b) {

FILE: board/project/protocol/crsf.c
  type crsf_sensor_type_t (line 56) | typedef enum crsf_sensor_type_t {
  type crsf_sensor_gps_formatted_t (line 80) | typedef struct crsf_sensor_gps_formatted_t {
  type crsf_sensor_vario_formatted_t (line 89) | typedef struct crsf_sensor_vario_formatted_t {
  type crsf_sensor_baro_formatted_t (line 93) | typedef struct crsf_sensor_baro_formatted_t {
  type crsf_sensor_battery_formatted_t (line 98) | typedef struct crsf_sensor_battery_formatted_t {
  type crsf_sensor_airspeed_formatted_t (line 105) | typedef struct crsf_sensor_airspeed_formatted_t {
  type crsf_sensor_rpm_formatted_t (line 109) | typedef struct crsf_sensor_rpm_formatted_t {
  type crsf_sensor_temp_formatted_t (line 114) | typedef struct crsf_sensor_temp_formatted_t {
  type crsf_sensor_voltages_formatted_t (line 119) | typedef struct crsf_sensor_voltages_formatted_t {
  type crsf_sensor_gps_time_formatted_t (line 124) | typedef struct crsf_sensor_gps_time_formatted_t {
  type crsf_sensor_gps_extended_formatted_t (line 134) | typedef struct crsf_sensor_gps_extended_formatted_t {
  type crsf_sensor_gps_t (line 149) | typedef struct crsf_sensor_gps_t {
  type crsf_sensor_attitude_formatted_t (line 158) | typedef struct crsf_sensor_attitude_formatted_t {
  type crsf_sensor_vario_t (line 164) | typedef struct crsf_sensor_vario_t {
  type crsf_sensor_baro_t (line 168) | typedef struct crsf_sensor_baro_t {
  type crsf_sensor_battery_t (line 173) | typedef struct crsf_sensor_battery_t {
  type crsf_sensor_airspeed_t (line 180) | typedef struct crsf_sensor_airspeed_t {
  type crsf_sensor_rpm_t (line 184) | typedef struct crsf_sensor_rpm_t {
  type crsf_sensor_temp_t (line 188) | typedef struct crsf_sensor_temp_t {
  type crsf_sensor_voltages_t (line 193) | typedef struct crsf_sensor_voltages_t {
  type crsf_sensor_gps_time_t (line 201) | typedef struct crsf_sensor_gps_time_t {
  type crsf_sensor_gps_extended_t (line 206) | typedef struct crsf_sensor_gps_extended_t {
  type crsf_sensor_attitude_t (line 220) | typedef struct crsf_sensor_attitude_t {
  type crsf_sensors_t (line 226) | typedef struct crsf_sensors_t {
  function crsf_task (line 248) | void crsf_task(void *parameters) {
  function format_sensor (line 261) | static uint8_t format_sensor(crsf_sensors_t *sensors, uint8_t type, uint...
  function uint (line 466) | static inline uint sensor_count(crsf_sensors_t *sensors) {
  function send_packet (line 473) | static void send_packet(crsf_sensors_t *sensors) {
  function get_crc (line 488) | static uint8_t get_crc(const uint8_t *ptr, uint32_t len) {
  function crc8 (line 496) | static uint8_t crc8(uint8_t crc, unsigned char a) {
  function set_config (line 508) | static void set_config(crsf_sensors_t *sensors) {

FILE: board/project/protocol/fbus.c
  type fbus_packet_t (line 39) | typedef struct fbus_packet_t {
  function fbus_task (line 63) | void fbus_task(void *parameters) {
  function sensor_task (line 77) | static void sensor_task(void *parameters) {
  function sensor_gpio_task (line 89) | static void sensor_gpio_task(void *parameters) {
  function sensor_void_task (line 113) | static void sensor_void_task(void *parameters) {
  function sensor_double_task (line 121) | static void sensor_double_task(void *parameters) {
  function sensor_coordinates_task (line 135) | static void sensor_coordinates_task(void *parameters) {
  function sensor_datetime_task (line 152) | static void sensor_datetime_task(void *parameters) {
  function sensor_cell_task (line 169) | static void sensor_cell_task(void *parameters) {
  function sensor_cell_individual_task (line 185) | static void sensor_cell_individual_task(void *parameters) {
  function process (line 221) | static void process(smartport_parameters_t *parameter) {
  function send_packet (line 248) | static void send_packet(uint8_t frame_id, uint16_t data_id, uint32_t val...
  function set_config (line 261) | static void set_config(smartport_parameters_t *parameter) {

FILE: board/project/protocol/fport.c
  function fport_task (line 58) | void fport_task(void *parameters) {
  function sensor_task (line 72) | static void sensor_task(void *parameters) {
  function sensor_gpio_task (line 84) | static void sensor_gpio_task(void *parameters) {
  function sensor_void_task (line 108) | static void sensor_void_task(void *parameters) {
  function sensor_double_task (line 116) | static void sensor_double_task(void *parameters) {
  function sensor_coordinates_task (line 130) | static void sensor_coordinates_task(void *parameters) {
  function sensor_datetime_task (line 147) | static void sensor_datetime_task(void *parameters) {
  function sensor_cell_task (line 164) | static void sensor_cell_task(void *parameters) {
  function sensor_cell_individual_task (line 180) | static void sensor_cell_individual_task(void *parameters) {
  function process (line 216) | static void process(smartport_parameters_t *parameter) {
  function send_packet (line 251) | static void send_packet(uint8_t frame_id, uint16_t data_id, uint32_t val...
  function set_config (line 276) | static void set_config(smartport_parameters_t *parameter) {

FILE: board/project/protocol/frsky_d.c
  type frsky_d_sensor_parameters_t (line 73) | typedef struct frsky_d_sensor_parameters_t {
  type frsky_d_sensor_cell_parameters_t (line 80) | typedef struct frsky_d_sensor_cell_parameters_t {
  function frsky_d_task (line 95) | void frsky_d_task(void *parameters) {
  function sensor_task (line 106) | static void sensor_task(void *parameters) {
  function sensor_cell_task (line 119) | static void sensor_cell_task(void *parameters) {
  function format (line 136) | static uint16_t format(uint8_t data_id, float value) {
  function send_byte (line 196) | static void send_byte(uint8_t c, bool header) {
  function send_packet (line 205) | static void send_packet(uint8_t data_id, uint16_t value) {
  function set_config (line 222) | static void set_config() {

FILE: board/project/protocol/ghst.c
  type ghst_sensor_pack_stat_formatted_t (line 52) | typedef struct ghst_sensor_pack_stat_formatted_t {
  type ghst_sensor_gps_primary_formatted_t (line 59) | typedef struct ghst_sensor_gps_primary_formatted_t {
  type ghst_sensor_gps_secondary_formatted_t (line 65) | typedef struct ghst_sensor_gps_secondary_formatted_t {
  type ghst_sensor_magbaro_formatted_t (line 74) | typedef struct ghst_sensor_magbaro_formatted_t {
  type ghst_sensor_pack_stat_t (line 81) | typedef struct ghst_sensor_pack_stat_t {
  type ghst_sensor_gps_primary_t (line 88) | typedef struct ghst_sensor_gps_primary_t {
  type ghst_sensor_gps_secondary_t (line 94) | typedef struct ghst_sensor_gps_secondary_t {
  type ghst_sensor_magbaro_t (line 105) | typedef struct ghst_sensor_magbaro_t {
  type ghst_sensors_t (line 112) | typedef struct ghst_sensors_t {
  function ghst_task (line 128) | void ghst_task(void *parameters) {
  function process (line 141) | static void process(ghst_sensors_t *sensors) {
  function format_sensor (line 158) | static uint8_t format_sensor(ghst_sensors_t *sensors, uint8_t type, uint...
  function uint (line 214) | static inline uint sensor_count(ghst_sensors_t *sensors) {
  function send_packet (line 221) | static void send_packet(ghst_sensors_t *sensors) {
  function get_crc (line 236) | static uint8_t get_crc(const uint8_t *ptr, uint32_t len) {
  function crc8 (line 244) | static uint8_t crc8(uint8_t crc, unsigned char a) {
  function set_config (line 256) | static void set_config(ghst_sensors_t *sensors) {

FILE: board/project/protocol/hitec.c
  type sensor_hitec_t (line 79) | typedef struct sensor_hitec_t {
  function hitec_task (line 108) | void hitec_task(void *parameters) {
  function hitec_i2c_handler (line 128) | void hitec_i2c_handler(void) {
  function i2c_handler (line 134) | static void i2c_handler(i2c_inst_t *i2c, i2c_slave_event_t event) {
  function alarm_reinit (line 178) | static int64_t alarm_reinit(alarm_id_t id, void *user_data) {
  function alarm_recovery (line 195) | static int64_t alarm_recovery(alarm_id_t id, void *user_data) {
  function i2c_bus_recovery (line 206) | static void i2c_bus_recovery(void) {
  function next_frame (line 251) | static int next_frame(void) {
  function format_packet (line 265) | static void format_packet(uint8_t frame, uint8_t *buffer) {
  function set_config (line 439) | static void set_config(void) {

FILE: board/project/protocol/hott.c
  type alarm_vario_t (line 189) | typedef enum alarm_vario_t {
  type alarm_airesc_t (line 198) | typedef enum alarm_airesc_t {
  type alarm_general_air_t (line 223) | typedef enum alarm_general_air_t {
  type alarm_general_gps_t (line 244) | typedef enum alarm_gps_t {
  type hott_sensor_vario_t (line 256) | typedef struct hott_sensor_vario_t {
  type hott_sensor_airesc_t (line 275) | typedef struct hott_sensor_airesc_t {
  type hott_sensor_electric_air_t (line 313) | typedef struct hott_sensor_electric_air_t {
  type hott_sensor_general_air_t (line 352) | typedef struct hott_sensor_general_air_t {
  type hott_sensor_gps_t (line 447) | typedef struct hott_sensor_gps_t {
  type hott_text_msg_t (line 486) | typedef struct hott_text_msg_t {
  type hott_sensors_t (line 500) | typedef struct hott_sensors_t {
  type trigger_t (line 508) | typedef struct trigger_t {
  type gps_triggers_t (line 515) | typedef enum gps_triggers_t {
  type vario_triggers_t (line 526) | typedef enum vario_triggers_t {
  type esc_triggers_t (line 533) | typedef enum esc_triggers_t {
  type general_triggers_t (line 543) | typedef enum general_triggers_t {
  type triggers_value_t (line 553) | typedef struct triggers_value_t {
  type triggers_menu_t (line 560) | typedef struct triggers_menu_t {
  type triggers_t (line 567) | typedef struct triggers_t {
  type vario_alarm_parameters_t (line 572) | typedef struct vario_alarm_parameters_t {
  function hott_task (line 595) | void hott_task(void *parameters) {
  function process (line 633) | static void process(hott_sensors_t *sensors, triggers_t *alarms) {
  function format_text_packet (line 647) | static void format_text_packet(triggers_t *alarms, hott_sensors_t *senso...
  function format_binary_packet (line 776) | static void format_binary_packet(triggers_t *alarms, hott_sensors_t *sen...
  function send_packet (line 1091) | static void send_packet(uint8_t *buffer, uint len) {
  function triggers_value_t (line 1103) | static triggers_value_t *alarms_read(void) {
  function module_alarms_save (line 1108) | static void module_alarms_save(triggers_value_t *triggers_value) {
  function get_crc (line 1118) | static uint8_t get_crc(const uint8_t *buffer, uint len) {
  function set_config (line 1127) | static void set_config(hott_sensors_t *sensors) {
  function interval_1000_callback (line 1612) | static int64_t interval_1000_callback(alarm_id_t id, void *parameters) {
  function interval_3000_callback (line 1623) | static int64_t interval_3000_callback(alarm_id_t id, void *parameters) {
  function interval_10000_callback (line 1635) | static int64_t interval_10000_callback(alarm_id_t id, void *parameters) {

FILE: board/project/protocol/ibus.c
  type sensor_ibus_t (line 105) | typedef struct sensor_ibus_t {
  function ibus_task (line 119) | void ibus_task(void *parameters) {
  function process (line 133) | static void process(sensor_ibus_t **sensor) {
  function send_packet (line 154) | static void send_packet(uint8_t command, uint8_t address, sensor_ibus_t ...
  function send_byte (line 211) | static void send_byte(uint8_t c, uint16_t *crc_p) {
  function check_crc (line 221) | static bool check_crc(uint8_t *data) {
  function add_sensor (line 229) | static void add_sensor(sensor_ibus_t *new_sensor, sensor_ibus_t **sensor...
  function format (line 238) | static int32_t format(uint8_t data_id, float value) {
  function set_config (line 259) | static void set_config(sensor_ibus_t **sensor, uint16_t sensormask) {

FILE: board/project/protocol/jetiex.c
  function jetiex_task (line 53) | void jetiex_task(void *parameters) {
  function jeti_create_telemetry_buffer (line 67) | uint8_t jeti_create_telemetry_buffer(uint8_t *buffer, bool packet_type, ...
  function jeti_add_sensor (line 101) | void jeti_add_sensor(sensor_jetiex_t *new_sensor, sensor_jetiex_t **sens...
  function jeti_set_config (line 110) | void jeti_set_config(sensor_jetiex_t **sensor) {
  function process (line 876) | static void process(uint *baudrate, sensor_jetiex_t **sensor) {
  function send_packet (line 910) | static void send_packet(uint8_t packet_id, sensor_jetiex_t **sensor) {
  function add_sensor_value (line 932) | static void add_sensor_value(uint8_t *buffer, uint8_t *buffer_index, uin...
  function add_sensor_text (line 1022) | static void add_sensor_text(uint8_t *buffer, uint8_t *buffer_index, uint...
  function timeout_callback (line 1040) | static int64_t timeout_callback(alarm_id_t id, void *parameters) {
  function crc8 (line 1051) | static uint8_t crc8(uint8_t *crc, uint8_t crc_length) {
  function update_crc8 (line 1060) | static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed) {
  function crc16 (line 1071) | static uint16_t crc16(uint8_t *p, uint16_t len) {
  function update_crc16 (line 1080) | static uint16_t update_crc16(uint16_t crc, uint8_t data) {

FILE: board/project/protocol/jetiex.h
  type sensor_jetiex_t (line 27) | typedef struct sensor_jetiex_t {

FILE: board/project/protocol/jetiex_sensor.c
  function jetiex_sensor_task (line 42) | void jetiex_sensor_task(void *parameters) {
  function send_packet (line 57) | static void send_packet(sensor_jetiex_t **sensor) {
  function alarm_packet (line 79) | static int64_t alarm_packet(alarm_id_t id, void *user_data) {

FILE: board/project/protocol/jr_dmss.c
  type sensor_t (line 53) | typedef enum sensor_t {
  function jr_dmss_task (line 88) | void jr_dmss_task(void *parameters) {
  function process (line 101) | static void process(float **sensor) {
  function send_packet (line 111) | static void send_packet(uint8_t address, float **sensor) {
  function crc_tab1e (line 238) | static uint8_t crc_tab1e(uint8_t data, uint8_t crc) {
  function crc8 (line 244) | static uint8_t crc8(uint8_t *buffer, uint8_t length) {
  function set_config (line 252) | static void set_config(float **sensor) {

FILE: board/project/protocol/multiplex.c
  type sensor_multiplex_t (line 57) | typedef struct sensor_multiplex_t {
  function multiplex_task (line 68) | void multiplex_task(void *parameters) {
  function process (line 81) | static void process(sensor_multiplex_t **sensor) {
  function send_packet (line 93) | static void send_packet(uint8_t address, sensor_multiplex_t *sensor) {
  function add_sensor (line 105) | static void add_sensor(sensor_multiplex_t *new_sensor, sensor_multiplex_...
  function format (line 113) | static int16_t format(uint8_t data_id, float value) {
  function set_config (line 132) | static void set_config(sensor_multiplex_t **sensors) {

FILE: board/project/protocol/sanwa.c
  type sanwa_sensor_formatted_t (line 49) | typedef struct sanwa_sensor_formatted_t {
  function sanwa_task (line 63) | void sanwa_task(void *parameters) {
  function process (line 88) | static void process(float **sensors) {
  function send_packet (line 104) | static void send_packet(float **sensors) {
  function format_sensor (line 121) | static void format_sensor(float *sensor, uint8_t type, sanwa_sensor_form...
  function get_crc (line 166) | static uint8_t get_crc(const uint8_t *buffer, uint len) {
  function set_config (line 172) | static void set_config(float **sensors) {

FILE: board/project/protocol/sbus.c
  type sensor_sbus_t (line 111) | typedef struct sensor_sbus_t {
  function sbus_task (line 130) | void sbus_task(void *parameters) {
  function process (line 146) | static void process() {
  function send_slot_callback (line 162) | static int64_t send_slot_callback(alarm_id_t id, void *parameters) {
  function send_slot (line 189) | static inline void send_slot(uint8_t slot) {
  function format (line 207) | static uint16_t format(uint8_t data_id, float value) {
  function get_slot_id (line 276) | static uint8_t get_slot_id(uint8_t slot) {
  function add_sensor (line 283) | static void add_sensor(uint8_t slot, sensor_sbus_t *new_sensor) { sbus_s...
  function set_config (line 285) | static void set_config(void) {

FILE: board/project/protocol/smartport.c
  function smartport_task (line 65) | void smartport_task(void *parameters) {
  function smartport_packet_t (line 85) | smartport_packet_t smartport_process_packet(smartport_parameters_t *para...
  function smartport_format (line 614) | int32_t smartport_format(uint16_t data_id, float value) {
  function smartport_format_double (line 634) | uint32_t smartport_format_double(uint16_t data_id, float value_l, float ...
  function smartport_format_coordinate (line 646) | uint32_t smartport_format_coordinate(coordinate_type_t type, float value) {
  function smartport_format_datetime (line 659) | uint32_t smartport_format_datetime(uint8_t type, uint32_t value) {
  function smartport_format_cell (line 669) | uint32_t smartport_format_cell(uint8_t cell_index, float value) {
  function smartport_get_crc (line 673) | uint8_t smartport_get_crc(uint8_t *data, uint len) {
  function smartport_send_byte (line 683) | void smartport_send_byte(uint8_t c, uint16_t *crcp) {
  function smartport_sensor_id_to_crc (line 699) | uint8_t smartport_sensor_id_to_crc(uint8_t sensor_id) {
  function smartport_sensor_crc_to_id (line 706) | uint8_t smartport_sensor_crc_to_id(uint8_t sensor_id_crc) {
  function process (line 715) | static void process(smartport_parameters_t *parameter) {
  function reboot_callback (line 773) | static int64_t reboot_callback(alarm_id_t id, void *user_data) { AIRCR_R...
  function sensor_task (line 775) | static void sensor_task(void *parameters) {
  function sensor_gpio_task (line 787) | static void sensor_gpio_task(void *parameters) {
  function sensor_void_task (line 811) | static void sensor_void_task(void *parameters) {
  function sensor_double_task (line 819) | static void sensor_double_task(void *parameters) {
  function sensor_coordinates_task (line 833) | static void sensor_coordinates_task(void *parameters) {
  function sensor_datetime_task (line 850) | static void sensor_datetime_task(void *parameters) {
  function sensor_cell_task (line 867) | static void sensor_cell_task(void *parameters) {
  function sensor_cell_individual_task (line 883) | static void sensor_cell_individual_task(void *parameters) {
  function packet_task (line 919) | static void packet_task(void *parameters) {
  function set_config (line 931) | static void set_config(smartport_parameters_t *parameter) {
  function send_packet (line 1929) | static void send_packet(uint8_t frame_id, uint16_t data_id, uint32_t val...

FILE: board/project/protocol/smartport.h
  type coordinate_type_t (line 108) | typedef enum coordinate_type_t {
  type datetime_type_t (line 113) | typedef enum datetime_type_t {
  type smartport_parameters_t (line 118) | typedef struct smartport_parameters_t {
  type smartport_sensor_parameters_t (line 123) | typedef struct smartport_sensor_parameters_t {
  type smartport_sensor_gpio_parameters_t (line 129) | typedef struct smartport_sensor_gpio_parameters_t {
  type smartport_sensor_double_parameters_t (line 136) | typedef struct smartport_sensor_double_parameters_t {
  type smartport_sensor_coordinate_parameters_t (line 143) | typedef struct smartport_sensor_coordinate_parameters_t {
  type smartport_sensor_datetime_parameters_t (line 150) | typedef struct smartport_sensor_datetime_parameters_t {
  type smartport_sensor_cell_parameters_t (line 157) | typedef struct smartport_sensor_cell_parameters_t {
  type smartport_sensor_cell_individual_parameters_t (line 163) | typedef struct smartport_sensor_cell_individual_parameters_t {
  type smartport_packet_parameters_t (line 169) | typedef struct smartport_packet_parameters_t {
  type smartport_packet_t (line 174) | typedef struct smartport_packet_t {

FILE: board/project/protocol/srxl.c
  function srxl_task (line 47) | void srxl_task(void *parameters) {
  function srxl_get_crc (line 62) | uint16_t srxl_get_crc(uint8_t *buffer, uint8_t length) {
  function srxl_crc16 (line 70) | uint16_t srxl_crc16(uint16_t crc, uint8_t data) {
  function uint (line 81) | uint srxl_sensors_count(void) {
  function process (line 89) | static void process(void) {
  function send_packet (line 109) | static void send_packet(void) {

FILE: board/project/protocol/srxl2.c
  function srxl2_task (line 57) | void srxl2_task(void *parameters) {
  function srxl2_send_handshake (line 80) | void srxl2_send_handshake(uart_inst_t *uart, uint8_t source_id, uint8_t ...
  function process (line 102) | static void process(void) {
  function send_packet (line 174) | static void send_packet(void) {
  function alarm_50ms (line 230) | static int64_t alarm_50ms(alarm_id_t id, void *user_data) {

FILE: board/project/protocol/srxl2.h
  type srxl2_handshake_t (line 19) | typedef struct srxl2_handshake_t {
  type srxl2_telemetry_t (line 32) | typedef struct srxl2_telemetry_t {

FILE: board/project/protocol/xbus.c
  function xbus_i2c_handler (line 59) | void xbus_i2c_handler(uint8_t address) { i2c_request_handler(address); }
  function xbus_task (line 61) | void xbus_task(void *parameters) {
  function xbus_format_sensor (line 78) | void xbus_format_sensor(uint8_t address, uint8_t *buffer) {
  function i2c_request_handler (line 343) | static void i2c_request_handler(uint8_t address) {
  function xbus_set_config (line 430) | void xbus_set_config(void) {
  function bcd8 (line 1010) | static uint8_t bcd8(float value, uint8_t precision) {
  function bcd16 (line 1019) | static uint16_t bcd16(float value, uint8_t precision) {
  function bcd32 (line 1028) | static uint32_t bcd32(float value, uint8_t precision) {
  function interval_250_callback (line 1037) | static int64_t interval_250_callback(alarm_id_t id, void *parameters) {
  function interval_500_callback (line 1044) | static int64_t interval_500_callback(alarm_id_t id, void *parameters) {
  function interval_1000_callback (line 1051) | static int64_t interval_1000_callback(alarm_id_t id, void *parameters) {
  function interval_1500_callback (line 1058) | static int64_t interval_1500_callback(alarm_id_t id, void *parameters) {
  function interval_2000_callback (line 1065) | static int64_t interval_2000_callback(alarm_id_t id, void *parameters) {
  function interval_3000_callback (line 1072) | static int64_t interval_3000_callback(alarm_id_t id, void *parameters) {

FILE: board/project/protocol/xbus.h
  type xbus_sensors_t (line 26) | typedef enum xbus_sensors_t {
  type xbus_airspeed_enum_t (line 45) | typedef enum xbus_airspeed_enum_t { XBUS_AIRSPEED_AIRSPEED, XBUS_AIRSPEE...
  type xbus_altitude_enum_t (line 47) | typedef enum xbus_altitude_enum_t { XBUS_ALTITUDE, XBUS_ALTITUDE_COUNT }...
  type xbus_gps_loc_enum_t (line 49) | typedef enum xbus_gps_loc_enum_t {
  type xbus_gps_stat_enum_t (line 58) | typedef enum xbus_gps_stat_enum_t {
  type xbus_energy_enum_t (line 68) | typedef enum xbus_energy_enum_t {
  type xbus_esc_enum_t (line 78) | typedef enum xbus_esc_enum_t {
  type xbus_battery_enum_t (line 89) | typedef enum xbus_battery_enum_t {
  type xbus_vario_enum_t (line 99) | typedef enum xbus_vario_enum_t { XBUS_VARIO_ALTITUDE, XBUS_VARIO_COUNT }...
  type xbus_rpm_volt_temp_enum_t (line 101) | typedef enum xbus_rpm_volt_temp_enum_t {
  type xbus_fuel_flow_enum_t (line 108) | typedef enum xbus_fuel_flow_enum_t {
  type xbus_stru_tele_digital_air_enum_t (line 114) | typedef enum xbus_stru_tele_digital_air_enum_t {
  type xbus_tele_lipomon_enum_t (line 119) | typedef enum xbus_tele_lipomon_enum_t {
  type xbus_tele_g_meter_enum_t (line 129) | typedef enum xbus_tele_g_meter_enum_t {
  type xbus_tele_gyro_enum_t (line 140) | typedef enum xbus_tele_gyro_enum_t {
  type xbus_multicyl_enum_t (line 147) | typedef enum xbus_multicyl_enum_t {
  type xbus_airspeed_t (line 153) | typedef struct xbus_airspeed_t {
  type xbus_altitude_t (line 160) | typedef struct xbus_altitude_t {
  type xbus_gps_loc_t (line 167) | typedef struct xbus_gps_loc_t {
  type xbus_gps_stat_t (line 178) | typedef struct xbus_gps_stat_t {
  type xbus_energy_t (line 187) | typedef struct xbus_energy_t {
  type xbus_esc_t (line 198) | typedef struct xbus_esc_t {
  type xbus_battery_t (line 212) | typedef struct xbus_battery_t {
  type xbus_vario_t (line 223) | typedef struct xbus_vario_t {
  type xbus_rpm_volt_temp_t (line 235) | typedef struct xbus_rpm_volt_temp_t {
  type xbus_fuel_flow_t (line 243) | typedef struct xbus_fuel_flow_t {
  type xbus_stru_tele_digital_air_t (line 255) | typedef struct xbus_stru_tele_digital_air_t {
  type xbus_tele_lipomon_t (line 262) | typedef struct xbus_tele_lipomon_t {
  type xbus_tele_g_meter_t (line 269) | typedef struct xbus_tele_g_meter_t {
  type xbus_tele_gyro_t (line 281) | typedef struct xbus_tele_gyro_t {
  type xbus_multi_cyl_t (line 292) | typedef struct xbus_multi_cyl_t {
  type xbus_sensor_gps_loc_t (line 317) | typedef struct xbus_sensor_gps_loc_t {
  type xbus_sensor_t (line 327) | typedef struct xbus_sensor_t {

FILE: board/project/sensor/airspeed.c
  function airspeed_task (line 17) | void airspeed_task(void *parameters) {

FILE: board/project/sensor/airspeed.h
  type airspeed_parameters_t (line 6) | typedef struct airspeed_parameters_t {

FILE: board/project/sensor/auto_offset.c
  function auto_offset_float_task (line 7) | void auto_offset_float_task(void *parameters) {
  function auto_offset_int_task (line 15) | void auto_offset_int_task(void *parameters) {

FILE: board/project/sensor/auto_offset.h
  type auto_offset_float_parameters_t (line 6) | typedef struct auto_offset_float_parameters_t {
  type auto_offset_int_parameters_t (line 13) | typedef struct auto_offset_int_parameters_t {

FILE: board/project/sensor/bmp180.c
  function bmp180_task (line 43) | void bmp180_task(void *parameters) {
  function read (line 64) | static void read(bmp180_parameters_t *parameter, bmp180_calibration_t *c...
  function begin (line 128) | static void begin(bmp180_parameters_t *parameter, bmp180_calibration_t *...

FILE: board/project/sensor/bmp180.h
  type bmp180_parameters_t (line 6) | typedef struct bmp180_parameters_t {
  type bmp180_calibration_t (line 12) | typedef struct bmp180_calibration_t {

FILE: board/project/sensor/bmp280.c
  function bmp280_task (line 66) | void bmp280_task(void *parameters) {
  function read (line 89) | static void read(bmp280_parameters_t *parameter, bmp280_calibration_t *c...
  function begin (line 142) | static void begin(bmp280_parameters_t *parameter, bmp280_calibration_t *...

FILE: board/project/sensor/bmp280.h
  type bmp280_parameters_t (line 6) | typedef struct bmp280_parameters_t {
  type bmp280_calibration_t (line 14) | typedef struct bmp280_calibration_t {

FILE: board/project/sensor/cell_count.c
  function cell_count_task (line 7) | void cell_count_task(void *parameters) {

FILE: board/project/sensor/cell_count.h
  type cell_count_parameters_t (line 6) | typedef struct cell_count_parameters_t {

FILE: board/project/sensor/current.c
  function current_task (line 10) | void current_task(void *parameters) {
  function current_read (line 48) | float current_read(uint8_t adc_num) {

FILE: board/project/sensor/current.h
  type current_parameters_t (line 6) | typedef struct current_parameters_t {

FILE: board/project/sensor/distance.c
  function coord_valid (line 16) | static inline bool coord_valid(float lat, float lon) {
  function distance_task (line 23) | void distance_task(void *parameters) {
  function degrees_to_radians (line 74) | static float degrees_to_radians(float degrees) { return degrees * (float...
  function get_distance_to_home_2d (line 76) | static float get_distance_to_home_2d(float lat, float lon, float lat_ini...

FILE: board/project/sensor/distance.h
  type distance_parameters_t (line 6) | typedef struct distance_parameters_t {

FILE: board/project/sensor/esc_apd_f.c
  function esc_apd_f_task (line 17) | void esc_apd_f_task(void *parameters) {
  function process (line 49) | static void process(esc_apd_f_parameters_t *parameter) {
  function update_crc8 (line 75) | static uint8_t update_crc8(uint8_t crc, uint8_t crc_seed) {
  function get_crc8 (line 83) | static uint8_t get_crc8(uint8_t *buffer, uint8_t lenght) {

FILE: board/project/sensor/esc_apd_f.h
  type esc_apd_f_parameters_t (line 6) | typedef struct esc_apd_f_parameters_t {

FILE: board/project/sensor/esc_apd_hv.c
  function esc_apd_hv_task (line 18) | void esc_apd_hv_task(void *parameters) {
  function process (line 50) | static void process(esc_apd_hv_parameters_t *parameter) {
  function get_temperature (line 74) | static float get_temperature(uint16_t raw) {
  function get_crc16 (line 95) | static uint16_t get_crc16(uint8_t *buffer) {

FILE: board/project/sensor/esc_apd_hv.h
  type esc_apd_hv_parameters_t (line 6) | typedef struct esc_apd_hv_parameters_t {

FILE: board/project/sensor/esc_castle.c
  function esc_castle_task (line 16) | void esc_castle_task(void *parameters) {
  function castle_link_handler (line 58) | static void castle_link_handler(castle_link_telemetry_t packet) {

FILE: board/project/sensor/esc_castle.h
  type esc_castle_parameters_t (line 22) | typedef struct esc_castle_parameters_t {

FILE: board/project/sensor/esc_hw3.c
  function esc_hw3_task (line 16) | void esc_hw3_task(void *parameters) {
  function process (line 31) | static void process(esc_hw3_parameters_t *parameter) {
  function timeout_callback (line 49) | static int64_t timeout_callback(alarm_id_t id, void *parameters) {

FILE: board/project/sensor/esc_hw3.h
  type esc_hw3_parameters_t (line 6) | typedef struct esc_hw3_parameters_t {

FILE: board/project/sensor/esc_hw4.c
  function esc_hw4_task (line 30) | void esc_hw4_task(void *parameters) {
  function process (line 77) | static void process(esc_hw4_parameters_t *parameter, uint *current_raw) {
  function get_voltage (line 140) | float get_voltage(uint16_t voltage_raw, esc_hw4_parameters_t *parameter) {
  function get_temperature (line 144) | float get_temperature(uint16_t temperature_raw) {
  function get_current (line 153) | float get_current(uint raw, int offset, float multiplier) {

FILE: board/project/sensor/esc_hw4.h
  type esc_hw4_parameters_t (line 6) | typedef struct esc_hw4_parameters_t {

FILE: board/project/sensor/esc_hw5.c
  function esc_hw5_task (line 18) | void esc_hw5_task(void *parameters) {
  function process (line 90) | static void process(esc_hw5_parameters_t *parameter) {
  function calculate_crc16 (line 132) | static uint16_t calculate_crc16(uint8_t const *buffer, uint lenght) {

FILE: board/project/sensor/esc_hw5.h
  type esc_hw5_parameters_t (line 6) | typedef struct esc_hw5_parameters_t {

FILE: board/project/sensor/esc_kontronik.c
  function esc_kontronik_task (line 14) | void esc_kontronik_task(void *parameters) {
  function process (line 50) | static void process(esc_kontronik_parameters_t *parameter) {

FILE: board/project/sensor/esc_kontronik.h
  type esc_kontronik_parameters_t (line 6) | typedef struct esc_kontronik_parameters_t {

FILE: board/project/sensor/esc_omp_m4.c
  type esc_omp_m4_packet_t (line 13) | typedef struct esc_omp_m4_packet_t {
  function esc_omp_m4_task (line 31) | void esc_omp_m4_task(void *parameters) {
  function process (line 66) | static void process(esc_omp_m4_parameters_t *parameter) {

FILE: board/project/sensor/esc_omp_m4.h
  type esc_omp_m4_parameters_t (line 6) | typedef struct esc_omp_m4_parameters_t {

FILE: board/project/sensor/esc_openyge.c
  function esc_openyge_task (line 22) | void esc_openyge_task(void *parameters) {
  function process (line 74) | static void process(esc_openyge_parameters_t *parameter) {
  function calculate_crc16_with_seed (line 200) | static uint16_t calculate_crc16_with_seed(uint8_t *data, uint8_t length,...
  function crc_mode_t (line 218) | static crc_mode_t detect_crc_mode(uint8_t *frame, uint8_t frame_len) {
  function validate_crc (line 262) | static bool validate_crc(uint8_t *frame, uint8_t frame_len, crc_mode_t m...

FILE: board/project/sensor/esc_openyge.h
  type crc_mode_t (line 6) | typedef enum {
  type esc_openyge_parameters_t (line 18) | typedef struct esc_openyge_parameters_t {

FILE: board/project/sensor/esc_pwm.c
  function esc_pwm_task (line 23) | void esc_pwm_task(void *parameters) {
  function read (line 40) | static void read(esc_pwm_parameters_t *parameter) {
  function capture_pin_0_handler (line 55) | static void capture_pin_0_handler(uint counter, edge_type_t edge) {
  function timeout_callback (line 69) | static int64_t timeout_callback(alarm_id_t id, void *parameters) {

FILE: board/project/sensor/esc_pwm.h
  type esc_hw3_parameters_t (line 6) | typedef esc_hw3_parameters_t esc_pwm_parameters_t;

FILE: board/project/sensor/esc_ztw.c
  type esc_ztw_packet_t (line 13) | typedef struct esc_ztw_packet_t {
  function esc_ztw_task (line 35) | void esc_ztw_task(void *parameters) {
  function process (line 72) | static void process(esc_ztw_parameters_t *parameter) {

FILE: board/project/sensor/esc_ztw.h
  type esc_ztw_parameters_t (line 6) | typedef struct esc_ztw_parameters_t {

FILE: board/project/sensor/fuel_meter.c
  function fuel_meter_task (line 20) | void fuel_meter_task(void *parameters) {
  function read (line 39) | static void read(fuel_meter_parameters_t *parameter) {
  function capture_pin_0_handler (line 50) | static void capture_pin_0_handler(uint counter, edge_type_t edge) {

FILE: board/project/sensor/fuel_meter.h
  type fuel_meter_parameters_t (line 6) | typedef struct fuel_meter_parameters_t {

FILE: board/project/sensor/gpio.c
  function gpio_task (line 9) | void gpio_task(void *parameters) {

FILE: board/project/sensor/gpio.h
  type gpio_parameters_t (line 6) | typedef struct gpio_parameters_t {

FILE: board/project/sensor/gps.c
  type ublox_msg_info_t (line 41) | typedef struct ublox_msg_info_t {
  type ublox_navpvt_t (line 47) | typedef struct ublox_navpvt_t {
  type ublox_navdop_t (line 85) | typedef struct ublox_navdop_t {
  type alarm_parameters_t (line 98) | typedef struct alarm_parameters_t {
  function gps_task (line 120) | void gps_task(void *parameters) {
  function process (line 194) | static void process(gps_parameters_t *parameter) {
  function set_home_altitude (line 331) | static bool set_home_altitude(uint fix_type) {
  function parser (line 347) | static void parser(uint8_t nmea_cmd, uint8_t cmd_field, uint8_t *buffer,...
  function set_ublox_config (line 423) | static void set_ublox_config(uint rate) {
  function set_nmea_config (line 437) | static void set_nmea_config(uint rate) {
  function set_baudrate (line 451) | static void set_baudrate(uint baudrate) {
  function nmea_msg (line 465) | static void nmea_msg(char *cmd, bool enable) {
  function ubx_cfg_msg (line 471) | static void ubx_cfg_msg(uint8_t class, uint8_t id, bool enable) {
  function ubx_cfg_rate (line 476) | static void ubx_cfg_rate(uint16_t rate) {
  function ubx_cfg_cfg (line 482) | static void ubx_cfg_cfg(void) {
  function send_ublox_message (line 488) | static inline void send_ublox_message(uint8_t *buf, uint len) {

FILE: board/project/sensor/gps.h
  type gps_parameters_t (line 6) | typedef struct gps_parameters_t {

FILE: board/project/sensor/ina3221.c
  function ina3221_task (line 34) | void ina3221_task(void *parameters) {
  function begin (line 55) | static void begin(ina3221_parameters_t *parameter) {
  function read (line 82) | static void read(ina3221_parameters_t *parameter) {

FILE: board/project/sensor/ina3221.h
  type ina3221_parameters_t (line 6) | typedef struct ina3221_parameters_t {

FILE: board/project/sensor/mpu6050.c
  type mpu6050_calibration_t (line 36) | typedef struct mpu6050_calibration_t {
  type mpu6050_acceleration_t (line 41) | typedef struct mpu6050_acceleration_t {
  type mpu6050_gyro_t (line 45) | typedef struct mpu6050_gyro_t {
  function mpu6050_task (line 57) | void mpu6050_task(void *parameters) {
  function read (line 121) | static void read(mpu6050_parameters_t *parameter, mpu6050_calibration_t ...
  function mpu6050_acceleration_t (line 167) | static mpu6050_acceleration_t read_acc(uint8_t address, float accel_divi...
  function mpu6050_gyro_t (line 184) | static mpu6050_gyro_t read_gyro(uint8_t address, float gyro_divider) {
  function begin (line 201) | static void begin(mpu6050_parameters_t *parameter, mpu6050_calibration_t...
  function calibrate_imu (line 244) | static void calibrate_imu(uint8_t address, mpu6050_calibration_t *calibr...

FILE: board/project/sensor/mpu6050.h
  type mpu6050_parameters_t (line 6) | typedef struct mpu6050_parameters_t {

FILE: board/project/sensor/ms5611.c
  function ms5611_task (line 42) | void ms5611_task(void *parameters) {
  function read (line 63) | static void read(ms5611_parameters_t *parameter, ms5611_calibration_t *c...
  function begin (line 119) | static void begin(ms5611_parameters_t *parameter, ms5611_calibration_t *...

FILE: board/project/sensor/ms5611.h
  type ms5611_parameters_t (line 6) | typedef struct ms5611_parameters_t {
  type ms5611_calibration_t (line 13) | typedef struct ms5611_calibration_t {

FILE: board/project/sensor/ntc.c
  function ntc_task (line 17) | void ntc_task(void *parameters) {

FILE: board/project/sensor/ntc.h
  type ntc_parameters_t (line 6) | typedef struct ntc_parameters_t {

FILE: board/project/sensor/pwm_out.c
  function pwm_out_task (line 8) | void pwm_out_task(void *parameters) {

FILE: board/project/sensor/smart_esc.c
  type srxl2_smart_bat_realtime_t (line 34) | typedef struct srxl2_smart_bat_realtime_t {
  type srxl2_smart_bat_cells_1_t (line 45) | typedef struct srxl2_smart_bat_cells_1_t {
  type srxl2_smart_bat_cells_2_t (line 58) | typedef struct srxl2_smart_bat_cells_2_t {
  type srxl2_smart_bat_cells_3_t (line 71) | typedef struct srxl2_smart_bat_cells_3_t {
  type srxl2_smart_bat_id_t (line 84) | typedef struct srxl2_smart_bat_id_t {
  type srxl2_smart_bat_limits_t (line 95) | typedef struct srxl2_smart_bat_limits_t {
  type srxl2_channel_data_t (line 109) | typedef struct srxl2_channel_data_t {
  type srxl2_control_packet_t (line 117) | typedef struct srxl2_control_packet_t {
  function smart_esc_task (line 142) | void smart_esc_task(void *parameters) {
  function process (line 180) | static void process(smart_esc_parameters_t *parameter) {
  function read_packet (line 218) | static void read_packet(uint8_t *buffer, smart_esc_parameters_t *paramet...
  function send_packet (line 313) | static void send_packet(void) {
  function capture_pwm_throttle_handler (line 345) | static void capture_pwm_throttle_handler(uint counter, edge_type_t edge) {
  function capture_pwm_reverse_handler (line 366) | static void capture_pwm_reverse_handler(uint counter, edge_type_t edge) {
  function timeout_throttle_callback (line 383) | static int64_t timeout_throttle_callback(alarm_id_t id, void *user_data) {
  function timeout_reverse_callback (line 389) | static int64_t timeout_reverse_callback(alarm_id_t id, void *user_data) {
  function alarm_packet (line 395) | static int64_t alarm_packet(alarm_id_t id, void *user_data) {

FILE: board/project/sensor/smart_esc.h
  type smart_esc_parameters_t (line 6) | typedef struct smart_esc_parameters_t {

FILE: board/project/sensor/voltage.c
  function voltage_task (line 8) | void voltage_task(void *parameters) {

FILE: board/project/sensor/voltage.h
  type voltage_parameters_t (line 6) | typedef struct voltage_parameters_t {

FILE: board/project/sensor/vspeed.c
  function vspeed_task (line 11) | void vspeed_task(void *parameters) {

FILE: board/project/sensor/vspeed.h
  type vspeed_parameters_t (line 6) | typedef struct vspeed_parameters_t {

FILE: board/project/sensor/xgzp68xxd.c
  function xgzp68xxd_task (line 26) | void xgzp68xxd_task(void *parameters) {
  function read (line 43) | static void read(xgzp68xxd_parameters_t *parameter) {
  function begin (line 62) | static void begin(void) {

FILE: board/project/sensor/xgzp68xxd.h
  type xgzp68xxd_parameters_t (line 6) | typedef struct xgzp68xxd_parameters_t {

FILE: board/project/serial_monitor.c
  function serial_monitor_task (line 13) | void serial_monitor_task(void *parameters) {
  function process (line 43) | static void process(config_t *config) {

FILE: board/project/sim_rx.c
  function sim_rx_task (line 26) | void sim_rx_task(void *parameters) {
  function process (line 40) | static void process(rx_protocol_t rx_protocol) {
  function ibus_send_data (line 377) | static void ibus_send_data(uint8_t command, uint8_t address) {
  function ibus_send_byte (line 394) | void ibus_send_byte(uint8_t c, uint16_t *crcP) {
  function jetiex_crc16 (line 403) | static uint16_t jetiex_crc16(uint8_t *p, uint16_t len) {
  function jetiex_update_crc16 (line 412) | static uint16_t jetiex_update_crc16(uint16_t crc, uint8_t data) {
  function smartport_get_crc (line 420) | static uint8_t smartport_get_crc(uint8_t *data) {

FILE: board/project/sim_rx.h
  type sim_rx_parameters_t (line 8) | typedef struct sim_rx_parameters_t {

FILE: board/project/uart.c
  function uart0_begin (line 24) | void uart0_begin(uint baudrate, uint gpio_tx, uint gpio_rx, uint timeout...
  function uart1_begin (line 52) | void uart1_begin(uint baudrate, uint gpio_tx, uint gpio_rx, uint timeout...
  function uart0_timeout_callback (line 80) | static int64_t uart0_timeout_callback(alarm_id_t id, void *user_data) {
  function uart1_timeout_callback (line 88) | static int64_t uart1_timeout_callback(alarm_id_t id, void *user_data) {
  function uart_reset_queue_from_isr (line 96) | static void uart_reset_queue_from_isr(QueueHandle_t queue_handle, BaseTy...
  function uart0_rx_handler (line 103) | static void uart0_rx_handler() {
  function uart1_rx_handler (line 128) | static void uart1_rx_handler() {
  function uart0_read (line 155) | uint8_t uart0_read() {
  function uart1_read (line 161) | uint8_t uart1_read() {
  function uart0_read_bytes (line 167) | void uart0_read_bytes(uint8_t *data, uint8_t lenght) {
  function uart1_read_bytes (line 171) | void uart1_read_bytes(uint8_t *data, uint8_t lenght) {
  function uart0_write (line 175) | void uart0_write(uint8_t data) {
  function uart1_write (line 189) | void uart1_write(uint8_t data) {
  function uart0_write_bytes (line 203) | void uart0_write_bytes(uint8_t *data, uint8_t lenght) {
  function uart1_write_bytes (line 217) | void uart1_write_bytes(uint8_t *data, uint8_t lenght) {
  function uart0_available (line 231) | uint8_t uart0_available() { return uxQueueMessagesWaiting(context.uart0_...
  function uart1_available (line 233) | uint8_t uart1_available() { return uxQueueMessagesWaiting(context.uart1_...
  function uint (line 235) | uint uart0_get_time_elapsed() { return time_us_32() - uart0_timestamp; }
  function uint (line 237) | uint uart1_get_time_elapsed() { return time_us_32() - uart1_timestamp; }
  function uart0_set_timestamp (line 241) | void uart0_set_timestamp() { uart0_timestamp = time_us_32(); }
  function uart1_set_timestamp (line 243) | void uart1_set_timestamp() { uart1_timestamp = time_us_32(); }

FILE: board/project/uart_pio.c
  function uart_pio_begin (line 17) | void uart_pio_begin(uint baudrate, int gpio_tx, int gpio_rx, uint timeou...
  function uart_pio_timeout_callback (line 31) | static int64_t uart_pio_timeout_callback(alarm_id_t id, void *user_data) {
  function uart_pio_reset_queue_from_isr (line 40) | static void uart_pio_reset_queue_from_isr(BaseType_t *xHigherPriorityTas...
  function uart_pio_handler (line 47) | static void uart_pio_handler(uint8_t data) {
  function uart_pio_read (line 70) | uint8_t uart_pio_read(void) {
  function uart_pio_read_bytes (line 76) | void uart_pio_read_bytes(uint8_t *data, uint8_t lenght) {
  function uart_pio_write (line 82) | void uart_pio_write(uint32_t c) { uart_tx_write(c); }
  function uart_pio_write_bytes (line 84) | void uart_pio_write_bytes(void *data, uint8_t lenght) { uart_tx_write_by...
  function uart_pio_available (line 86) | uint8_t uart_pio_available(void) { return uxQueueMessagesWaiting(context...
  function uart_pio_tx_available (line 88) | uint8_t uart_pio_tx_available(void) {
  function uint (line 92) | uint uart_pio_get_time_elapsed(void) { return time_us_32() - uart_pio_ti...
  function uart_pio_remove (line 94) | void uart_pio_remove(void) {

FILE: board/project/usb.c
  function usb_task (line 20) | void usb_task() {
  function process_usb (line 29) | static void process_usb(int lenght) {
  function read_usb (line 93) | static int read_usb() {

FILE: include/shared.h
  type rx_protocol_t (line 8) | typedef enum rx_protocol_t : uint8_t {
  type esc_protocol_t (line 30) | typedef enum esc_protocol_t : uint8_t {
  type i2c_module_t (line 46) | typedef enum i2c_module_t : uint8_t { I2C_NONE, I2C_BMP280, I2C_MS5611, ...
  type analog_current_type_t (line 48) | typedef enum analog_current_type_t : uint8_t { CURRENT_TYPE_HALL, CURREN...
  type serial_monitor_format_t (line 50) | typedef enum serial_monitor_format_t : uint8_t { FORMAT_HEX, FORMAT_STRI...
  type gps_protocol_t (line 52) | typedef enum gps_protocol_t : uint8_t { UBLOX, NMEA } gps_protocol_t;
  type rx_protocol_t (line 56) | typedef enum rx_protocol_t {
  type esc_protocol_t (line 78) | typedef enum esc_protocol_t {
  type i2c_module_t (line 94) | typedef enum i2c_module_t { I2C_NONE, I2C_BMP280, I2C_MS5611, I2C_BMP180...
  type analog_current_type_t (line 96) | typedef enum analog_current_type_t { CURRENT_TYPE_HALL, CURRENT_TYPE_SHU...
  type serial_monitor_format_t (line 98) | typedef enum serial_monitor_format_t { FORMAT_HEX, FORMAT_STRING } seria...
  type gps_protocol_t (line 100) | typedef enum gps_protocol_t { UBLOX, NMEA } gps_protocol_t;
  type config_t (line 104) | typedef struct config_t {                            // smartport data_id

FILE: msrc_gui/circuitdialog.h
  function namespace (line 9) | namespace Ui {
  function class (line 13) | class CircuitDialog : public QDialog

FILE: msrc_gui/main.cpp
  function main (line 5) | int main(int argc, char *argv[])

FILE: msrc_gui/mainwindow.cpp
  function QStringList (line 933) | QStringList MainWindow::fillPortsInfo() {

FILE: msrc_gui/mainwindow.h
  function QT_BEGIN_NAMESPACE (line 20) | QT_BEGIN_NAMESPACE

FILE: msrc_gui_web/js/app.js
  function setConnected (line 197) | function setConnected() {
  function setDisconnected (line 207) | function setDisconnected() {
  function setStatus (line 221) | function setStatus(msg) {

FILE: msrc_gui_web/js/circuit.js
  constant CIRCUIT_IMAGES (line 6) | const CIRCUIT_IMAGES = {};
  constant CIRCUIT_IMAGE_LIST (line 7) | const CIRCUIT_IMAGE_LIST = [
  function preloadCircuitImages (line 20) | function preloadCircuitImages() {
  function generateCircuit (line 38) | function generateCircuit() {
  function drawOverlay (line 121) | function drawOverlay(ctx, name) {
  function initCircuit (line 128) | function initCircuit() {

FILE: msrc_gui_web/js/config_struct.js
  constant CONFIG_VERSION (line 11) | const CONFIG_VERSION = 2;
  constant RX_PROTOCOL (line 14) | const RX_PROTOCOL = {
  constant ESC_PROTOCOL (line 21) | const ESC_PROTOCOL = {
  function buildLayout (line 34) | function buildLayout() {
  constant LAYOUT (line 160) | const LAYOUT = buildLayout();
  constant CONFIG_SIZE (line 161) | const CONFIG_SIZE = LAYOUT.totalSize;
  function configDecode (line 168) | function configDecode(bytes) {
  function configEncode (line 194) | function configEncode(cfg) {
  function configDefault (line 217) | function configDefault() {

FILE: msrc_gui_web/js/serial.js
  constant HEADER (line 14) | const HEADER = 0x30;
  constant CMD_WRITE_CONFIG (line 15) | const CMD_WRITE_CONFIG = 0x30;
  constant CMD_REQUEST_CONFIG (line 16) | const CMD_REQUEST_CONFIG = 0x31;
  constant CMD_CONFIG_RESPONSE (line 17) | const CMD_CONFIG_RESPONSE = 0x32;
  constant CMD_DEBUG_ON (line 18) | const CMD_DEBUG_ON = 0x33;
  constant CMD_DEBUG_OFF (line 19) | const CMD_DEBUG_OFF = 0x34;
  constant CMD_DEFAULT_CONFIG (line 20) | const CMD_DEFAULT_CONFIG = 0x35;
  class SerialConnection (line 22) | class SerialConnection {
    method constructor (line 23) | constructor() {
    method isSupported (line 38) | static isSupported() {
    method requestPort (line 42) | async requestPort() {
    method connect (line 47) | async connect() {
    method disconnect (line 54) | async disconnect() {
    method _startReading (line 67) | async _startReading() {
    method _processBytes (line 92) | _processBytes(chunk) {
    method _write (line 127) | async _write(bytes) {
    method requestConfig (line 137) | async requestConfig() {
    method writeConfig (line 142) | async writeConfig(configBytes) {
    method enableDebug (line 150) | async enableDebug() {
    method disableDebug (line 156) | async disableDebug() {
    method writeDefaultConfig (line 161) | async writeDefaultConfig() {
    method onConfigReceived (line 165) | set onConfigReceived(fn) { this._onConfigReceived = fn; }
    method onDebugData (line 166) | set onDebugData(fn) { this._onDebugData = fn; }
    method onDisconnect (line 167) | set onDisconnect(fn) { this._onDisconnect = fn; }
  constant CDC_SET_LINE_CODING (line 177) | const CDC_SET_LINE_CODING = 0x20;
  constant CDC_SET_CONTROL_LINE_STATE (line 178) | const CDC_SET_CONTROL_LINE_STATE = 0x22;
  constant PICO_VID (line 181) | const PICO_VID = 0x2E8A;
  constant PICO_PID_CDC (line 182) | const PICO_PID_CDC = 0x000A;
  class WebUSBConnection (line 184) | class WebUSBConnection {
    method constructor (line 185) | constructor() {
    method isSupported (line 199) | static isSupported() {
    method requestPort (line 203) | async requestPort() {
    method connect (line 210) | async connect() {
    method _findEndpoints (line 255) | _findEndpoints() {
    method disconnect (line 290) | async disconnect() {
    method _startReading (line 302) | async _startReading() {
    method _processBytes (line 326) | _processBytes(chunk) {
    method _write (line 354) | async _write(bytes) {
    method requestConfig (line 359) | async requestConfig() {
    method writeConfig (line 364) | async writeConfig(configBytes) {
    method enableDebug (line 372) | async enableDebug() {
    method disableDebug (line 378) | async disableDebug() {
    method writeDefaultConfig (line 383) | async writeDefaultConfig() {
    method onConfigReceived (line 387) | set onConfigReceived(fn) { this._onConfigReceived = fn; }
    method onDebugData (line 388) | set onDebugData(fn) { this._onDebugData = fn; }
    method onDisconnect (line 389) | set onDisconnect(fn) { this._onDisconnect = fn; }
  function createConnection (line 397) | function createConnection() {

FILE: msrc_gui_web/js/ui.js
  function $ (line 8) | function $(id) { return document.getElementById(id); }
  function alphaToElements (line 10) | function alphaToElements(alpha) {
  function elementsToAlpha (line 14) | function elementsToAlpha(n) {
  function selectByValue (line 18) | function selectByValue(sel, val) {
  function selectedValue (line 28) | function selectedValue(sel) { return sel.options[sel.selectedIndex]?.val...
  function selectedText (line 29) | function selectedText(sel) { return sel.options[sel.selectedIndex]?.text...
  function show (line 31) | function show(el) { if (el) el.style.display = ''; }
  function hide (line 32) | function hide(el) { if (el) el.style.display = 'none'; }
  function showIf (line 33) | function showIf(el, cond) { if (el) el.style.display = cond ? '' : 'none...
  function setUiFromConfig (line 37) | function setUiFromConfig(cfg) {
  function getConfigFromUi (line 203) | function getConfigFromUi() {
  function updateVisibility (line 369) | function updateVisibility() {
  function updateEscOptions (line 460) | function updateEscOptions() {
  function updateCurrentSensorUI (line 491) | function updateCurrentSensorUI() {
  function updateToggleables (line 502) | function updateToggleables() {
  function bindUIEvents (line 514) | function bindUIEvents() {

FILE: msrc_gui_web/js/version.js
  constant APP_VERSION (line 1) | const APP_VERSION = '1.0.1';

FILE: msrc_gui_web/sw.js
  constant CACHE_NAME (line 7) | const CACHE_NAME = 'msrc-link-' + APP_VERSION;
  constant ASSETS (line 9) | const ASSETS = [
Condensed preview — 189 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (1,496K chars).
[
  {
    "path": ".clang-format",
    "chars": 52,
    "preview": "BasedOnStyle: Google\nIndentWidth: 4\nColumnLimit: 120"
  },
  {
    "path": ".gitattributes",
    "chars": 78,
    "preview": "case/** filter=lfs diff=lfs merge=lfs -text\ncase/** linguist-detectable=false\n"
  },
  {
    "path": ".github/copilot-instructions.md",
    "chars": 14848,
    "preview": "# MSRC – Copilot Instructions\n\n## Project Overview\n\nMSRC (Multi Sensor for RC) is a telemetry system for RC models runni"
  },
  {
    "path": ".github/workflows/build_release.yaml",
    "chars": 4683,
    "preview": "name: Build Release\n\non:\n  release:\n    types: [published]\n\nenv:\n  FIRMWARE_FILENAME: MSRC-RP2040_${{ github.ref_name }}"
  },
  {
    "path": ".github/workflows/ci_firmware.yaml",
    "chars": 1344,
    "preview": "# gh search commits --hash 272effd --repo dgatf/msrc\n\nname: CI - MSRC firmware\n\non:\n  workflow_dispatch: {}\n\njobs:\n  bui"
  },
  {
    "path": ".github/workflows/ci_msrc_link.yaml",
    "chars": 3937,
    "preview": "name: CI - MSRC Link\n\non:\n  workflow_dispatch: {}\n\njobs:\n  linux:\n    runs-on: ubuntu-22.04\n    permissions:\n        con"
  },
  {
    "path": ".github/workflows/dev_firmware.yaml",
    "chars": 1766,
    "preview": "name: Dev Release (Firmware)\n\non:\n  workflow_dispatch: {}\n  push:\n    branches:\n      - master\n    paths:\n      - board/"
  },
  {
    "path": ".github/workflows/dev_msrc_link.yaml",
    "chars": 5591,
    "preview": "name: Dev Release - MSRC Link\n\non:\n  workflow_dispatch: {}\n  push:\n    branches:\n      - master\n    paths:\n      - msrc_"
  },
  {
    "path": ".gitignore",
    "chars": 74,
    "preview": "misc\nbuild/\nbuild_*/\nmsrc_gui/msrc_gui.pro.user*\n\n### macOS ###\n.DS_Store\n"
  },
  {
    "path": ".gitmodules",
    "chars": 139,
    "preview": "[submodule \"board/freertos/FreeRTOS-Kernel\"]\n\tpath = board/freertos/FreeRTOS-Kernel\n\turl = https://github.com/FreeRTOS/F"
  },
  {
    "path": ".vscode/c_cpp_properties.json",
    "chars": 705,
    "preview": "{\n    \"configurations\": [\n        {\n            \"name\": \"Default\",\n            \"includePath\": [\n                \"${works"
  },
  {
    "path": ".vscode/launch.json",
    "chars": 1057,
    "preview": "{\n    \"version\": \"0.2.0\",\n    \"configurations\": [\n        {\n            \"name\": \"Pico Debug\",\n            \"cwd\": \"${work"
  },
  {
    "path": ".vscode/settings.json",
    "chars": 653,
    "preview": "{\n    // These settings tweaks to the cmake plugin will ensure\n    // that you debug using cortex-debug instead of tryin"
  },
  {
    "path": "LICENSE",
    "chars": 34496,
    "preview": "GNU GENERAL PUBLIC LICENSE\n\t Version 3, 29 June 2007\n\nCopyright (C) 2007 Free Software Foundation, Inc. <https://fsf.org"
  },
  {
    "path": "README.md",
    "chars": 2751,
    "preview": "# MSRC – Multi Sensor Telemetry for RC (RP2040)\n\n[![Donate](https://img.shields.io/badge/Donate-PayPal-green.svg)](https"
  },
  {
    "path": "board/CMakeLists.txt",
    "chars": 519,
    "preview": "cmake_minimum_required(VERSION 3.17.0)\r\n\r\ninclude(pico_sdk_import.cmake)\r\n\r\nproject(MSRC-RP2040)\r\n\r\ninclude_directories("
  },
  {
    "path": "board/freertos/CMakeLists.txt",
    "chars": 606,
    "preview": "set(PICO_SDK_FREERTOS_SOURCE FreeRTOS-Kernel)\r\n\r\nadd_library(freertos\r\n    ${PICO_SDK_FREERTOS_SOURCE}/event_groups.c\r\n "
  },
  {
    "path": "board/freertos/FreeRTOSConfig.h",
    "chars": 3685,
    "preview": "#ifndef FREERTOS_CONFIG_H\r\n#define FREERTOS_CONFIG_H\r\n\r\n/* Use Pico SDK ISR handlers */\r\n#define vPortSVCHandler        "
  },
  {
    "path": "board/pico_sdk_import.cmake",
    "chars": 2738,
    "preview": "# This is a copy of <PICO_SDK_PATH>/external/pico_sdk_import.cmake\n\n# This can be dropped into an external project to he"
  },
  {
    "path": "board/project/CMakeLists.txt",
    "chars": 787,
    "preview": "include_directories(. pio protocol sensor)\r\n\r\nadd_executable(${PROJECT_NAME})\r\n\r\nadd_subdirectory(protocol)\r\nadd_subdire"
  },
  {
    "path": "board/project/common.c",
    "chars": 2758,
    "preview": "\n#include \"common.h\"\n\n#include <math.h>\n#include <stdlib.h>\n\n#include \"hardware/adc.h\"\n#include \"hardware/i2c.h\"\n#includ"
  },
  {
    "path": "board/project/common.h",
    "chars": 2369,
    "preview": "#ifndef COMMON_H\n#define COMMON_H\n\n#include <FreeRTOS.h>\n#include <queue.h>\n#include <task.h>\n\n#include \"constants.h\"\n#i"
  },
  {
    "path": "board/project/config.c",
    "chars": 10206,
    "preview": "#include \"config.h\"\n\n#include <hardware/flash.h>\n#include <hardware/sync.h>\n#include <stdio.h>\n#include <string.h>\n\n#inc"
  },
  {
    "path": "board/project/config.h",
    "chars": 382,
    "preview": "#ifndef CONFIG_H\n#define CONFIG_H\n\n#include \"common.h\"\n\n#define CONFIG_FORZE_WRITE false\n#define CONFIG_VERSION 2\n#defin"
  },
  {
    "path": "board/project/constants.h",
    "chars": 4684,
    "preview": "#ifndef CONSTANTS_H\n#define CONSTANTS_H\n\n/* Pins */\n#define UART0_TX_GPIO 0       // receiver rx\n#define UART0_RX_GPIO 1"
  },
  {
    "path": "board/project/dbg_rb.c",
    "chars": 1405,
    "preview": "#include \"dbg_rb.h\"\n\nstatic uint8_t *s_buf = NULL;\nstatic size_t   s_cap = 0;\nstatic volatile size_t s_head = 0; // writ"
  },
  {
    "path": "board/project/dbg_rb.h",
    "chars": 631,
    "preview": "#pragma once\n\n#include <stddef.h>\n#include <stdint.h>\n#include <stdbool.h>\n\n#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n// R"
  },
  {
    "path": "board/project/dbg_task.c",
    "chars": 2886,
    "preview": "// dbg_task.c\n\n#include \"dbg_task.h\"\n#include \"dbg_rb.h\"\n\n#include <stdio.h>\n#include <stdarg.h>\n#include <string.h>\n\n#i"
  },
  {
    "path": "board/project/dbg_task.h",
    "chars": 765,
    "preview": "#pragma once\n\n#include <stddef.h>\n#include <stdint.h>\n\n#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n// Must be called once at"
  },
  {
    "path": "board/project/led.c",
    "chars": 687,
    "preview": "#include \"led.h\"\n\n#include \"pico/stdlib.h\"\n#include \"ws2812.h\"\n\nvoid led_task() {\n    const uint WS2812_PIN = 16;\n    gp"
  },
  {
    "path": "board/project/led.h",
    "chars": 101,
    "preview": "#ifndef LED_H\n#define LED_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid led_task();\n\n#endif"
  },
  {
    "path": "board/project/main.c",
    "chars": 6093,
    "preview": "#include <stdio.h>\r\n\r\n#include \"config.h\"\r\n#include \"frsky_d.h\"\r\n#include \"hitec.h\"\r\n#include \"ibus.h\"\r\n#include \"jetiex"
  },
  {
    "path": "board/project/pio/CMakeLists.txt",
    "chars": 778,
    "preview": "target_sources(${PROJECT_NAME} PRIVATE\r\n    capture_edge.c\r\n    castle_link.c\r\n    i2c_multi.c\r\n    uart_rx.c\r\n    ws281"
  },
  {
    "path": "board/project/pio/capture_edge.c",
    "chars": 8953,
    "preview": "/*\n * Copyright (c) 2022, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style l"
  },
  {
    "path": "board/project/pio/capture_edge.h",
    "chars": 760,
    "preview": "/*\n * Copyright (c) 2022, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style l"
  },
  {
    "path": "board/project/pio/capture_edge.pio",
    "chars": 733,
    "preview": "/*\n * Copyright (c) 2022, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style l"
  },
  {
    "path": "board/project/pio/castle_link.c",
    "chars": 4665,
    "preview": "#include \"castle_link.h\"\n\n#include <math.h>\n\n#include \"hardware/irq.h\"\n#include \"hardware/pio.h\"\n#include \"pico/stdlib.h"
  },
  {
    "path": "board/project/pio/castle_link.h",
    "chars": 1195,
    "preview": "#ifndef PIO_CASTLE\n#define PIO_CASTLE\n\n#include \"castle_link.pio.h\"\n\n/*                 castle telemetry\n\n    index   el"
  },
  {
    "path": "board/project/pio/castle_link.pio",
    "chars": 1144,
    "preview": "/**\n * Copyright (c) 2022, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style "
  },
  {
    "path": "board/project/pio/i2c_multi.c",
    "chars": 14837,
    "preview": "#include \"i2c_multi.h\"\n\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"hardware/irq.h\"\n#include \"hardware/pio.h\"\n#inc"
  },
  {
    "path": "board/project/pio/i2c_multi.h",
    "chars": 1353,
    "preview": "#ifndef I2C_MULTI\n#define I2C_MULTI\n\n#include \"hardware/pio.h\"\n#include \"common.h\"\n\ntypedef enum i2c_multi_status_t { I2"
  },
  {
    "path": "board/project/pio/i2c_multi.pio",
    "chars": 2040,
    "preview": "/**\n * -------------------------------------------------------------------------------\n * \n * Copyright (c) 2022, Daniel"
  },
  {
    "path": "board/project/pio/uart_rx.c",
    "chars": 1919,
    "preview": "#include \"uart_rx.h\"\n\n#include \"hardware/clocks.h\"\n#include \"hardware/irq.h\"\n#include \"hardware/pio.h\"\n#include \"pico/st"
  },
  {
    "path": "board/project/pio/uart_rx.h",
    "chars": 256,
    "preview": "#ifndef UART_RX\n#define UART_RX\n\n#include \"uart_rx.pio.h\"\n\ntypedef void (*uart_rx_handler_t)(uint8_t data);\n\nuint uart_r"
  },
  {
    "path": "board/project/pio/uart_rx.pio",
    "chars": 626,
    "preview": "/**\n * Copyright (c) 2022, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style "
  },
  {
    "path": "board/project/pio/uart_tx.c",
    "chars": 2250,
    "preview": "#include \"uart_tx.h\"\n\n#include \"hardware/clocks.h\"\n#include \"hardware/pio.h\"\n#include \"pico/stdlib.h\"\n\nstatic uint sm_, "
  },
  {
    "path": "board/project/pio/uart_tx.h",
    "chars": 277,
    "preview": "#ifndef UART_TX\n#define UART_TX\n\n#include \"uart_tx.pio.h\"\n\nuint uart_tx_init(PIO pio, uint pin, uint baudrate, uint data"
  },
  {
    "path": "board/project/pio/uart_tx.pio",
    "chars": 679,
    "preview": "/**\n * Copyright (c) 2025, Daniel Gorbea\n * All rights reserved.\n *\n * This source code is licensed under the MIT-style "
  },
  {
    "path": "board/project/pio/ws2812.c",
    "chars": 1164,
    "preview": "#include \"ws2812.h\"\n\n#include \"hardware/clocks.h\"\n#include \"hardware/pio.h\"\n#include \"pico/stdlib.h\"\n\nstatic uint sm_;\ns"
  },
  {
    "path": "board/project/pio/ws2812.h",
    "chars": 169,
    "preview": "#ifndef WS2812_H\n#define WS2812_H\n\n#include \"ws2812.pio.h\"\n\nvoid ws2812_init(PIO pio, uint pin, float freq);\nvoid put_pi"
  },
  {
    "path": "board/project/pio/ws2812.pio",
    "chars": 553,
    "preview": ";\n; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.\n;\n; SPDX-License-Identifier: BSD-3-Clause\n;\n\n.program ws2812\n.side_se"
  },
  {
    "path": "board/project/protocol/CMakeLists.txt",
    "chars": 290,
    "preview": "target_sources(${PROJECT_NAME} PRIVATE\r\n    frsky_d.c\r\n    hitec.c\r\n    ibus.c\r\n    jetiex.c\r\n    multiplex.c\r\n    sbus."
  },
  {
    "path": "board/project/protocol/crsf.c",
    "chars": 51010,
    "preview": "#include \"crsf.h\"\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n\n#include \"airspeed.h\"\n#"
  },
  {
    "path": "board/project/protocol/crsf.h",
    "chars": 120,
    "preview": "#ifndef CRSF_H\n#define CRSF_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid crsf_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/fbus.c",
    "chars": 69136,
    "preview": "#include \"fbus.h\"\n\n#include <math.h>\n#include <semphr.h>\n#include <stdio.h>\n#include <string.h>\n\n#include \"airspeed.h\"\n#"
  },
  {
    "path": "board/project/protocol/fbus.h",
    "chars": 120,
    "preview": "#ifndef FBUS_H\n#define FBUS_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid fbus_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/fport.c",
    "chars": 69346,
    "preview": "#include \"fport.h\"\n\n#include <math.h>\n#include <semphr.h>\n#include <stdio.h>\n#include <string.h>\n\n#include \"airspeed.h\"\n"
  },
  {
    "path": "board/project/protocol/fport.h",
    "chars": 123,
    "preview": "#ifndef FPORT_H\n#define FPORT_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid fport_task(void *parameters);\n\n#en"
  },
  {
    "path": "board/project/protocol/frsky_d.c",
    "chars": 63075,
    "preview": "#include \"frsky_d.h\"\n\n#include <math.h>\n#include <semphr.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"airspeed.h"
  },
  {
    "path": "board/project/protocol/frsky_d.h",
    "chars": 129,
    "preview": "#ifndef FRSKY_D_H\n#define FRSKY_D_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid frsky_d_task(void *parameters)"
  },
  {
    "path": "board/project/protocol/ghst.c",
    "chars": 15772,
    "preview": "#include \"ghst.h\"\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n\n#include \"airspeed.h\"\n#"
  },
  {
    "path": "board/project/protocol/ghst.h",
    "chars": 120,
    "preview": "#ifndef GHST_H\n#define GHST_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid ghst_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/hitec.c",
    "chars": 36975,
    "preview": "#include \"hitec.h\"\n\n#include <math.h>\n#include <pico/i2c_slave.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bm"
  },
  {
    "path": "board/project/protocol/hitec.h",
    "chars": 153,
    "preview": "#ifndef HITEC_H\n#define HITEC_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid hitec_task(void *parameters);\nvoid"
  },
  {
    "path": "board/project/protocol/hott.c",
    "chars": 80695,
    "preview": "#include \"hott.h\"\n\n#include <hardware/flash.h>\n#include <hardware/sync.h>\n#include <math.h>\n#include <stdio.h>\n#include "
  },
  {
    "path": "board/project/protocol/hott.h",
    "chars": 120,
    "preview": "#ifndef HOTT_H\n#define HOTT_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid hott_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/ibus.c",
    "chars": 48710,
    "preview": "#include \"ibus.h\"\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#"
  },
  {
    "path": "board/project/protocol/ibus.h",
    "chars": 120,
    "preview": "#ifndef IBUS_H\n#define IBUS_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid ibus_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/jetiex.c",
    "chars": 58901,
    "preview": "#include \"jetiex.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280.h\""
  },
  {
    "path": "board/project/protocol/jetiex.h",
    "chars": 1073,
    "preview": "#ifndef JETIEX_H\n#define JETIEX_H\n\n#include \"common.h\"\n\n#define JETIEX_TYPE_INT6 0\n#define JETIEX_TYPE_INT14 1\n#define J"
  },
  {
    "path": "board/project/protocol/jetiex_sensor.c",
    "chars": 2544,
    "preview": "#include \"jetiex_sensor.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bm"
  },
  {
    "path": "board/project/protocol/jetiex_sensor.h",
    "chars": 167,
    "preview": "#ifndef JETIEX_SENSOR_H\n#define JETIEX_SENSOR_H\n\n#include \"common.h\"\n#include \"jetiex.h\"\n\nextern context_t context;\n\nvoi"
  },
  {
    "path": "board/project/protocol/jr_dmss.c",
    "chars": 33232,
    "preview": "#include \"jr_dmss.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280.h"
  },
  {
    "path": "board/project/protocol/jr_dmss.h",
    "chars": 129,
    "preview": "#ifndef JR_DMSS_H\n#define JR_DMSS_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid jr_dmss_task(void *parameters)"
  },
  {
    "path": "board/project/protocol/multiplex.c",
    "chars": 34388,
    "preview": "#include \"multiplex.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280"
  },
  {
    "path": "board/project/protocol/multiplex.h",
    "chars": 135,
    "preview": "#ifndef MULTIPLEX_H\n#define MULTIPLEX_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid multiplex_task(void *param"
  },
  {
    "path": "board/project/protocol/sanwa.c",
    "chars": 14836,
    "preview": "#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n"
  },
  {
    "path": "board/project/protocol/sanwa.h",
    "chars": 123,
    "preview": "#ifndef SANWA_H\n#define SANWA_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid sanwa_task(void *parameters);\n\n#en"
  },
  {
    "path": "board/project/protocol/sbus.c",
    "chars": 42981,
    "preview": "#include \"sbus.h\"\n\n#include <math.h>\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#"
  },
  {
    "path": "board/project/protocol/sbus.h",
    "chars": 121,
    "preview": "#ifndef SBUS_H\n#define SBUS_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid sbus_task(void *parameters);\n\n#endif"
  },
  {
    "path": "board/project/protocol/smartport.c",
    "chars": 94799,
    "preview": "#include \"smartport.h\"\n\n#include <math.h>\n#include <semphr.h>\n#include <stdio.h>\n#include <string.h>\n\n#include \"airspeed"
  },
  {
    "path": "board/project/protocol/smartport.h",
    "chars": 6402,
    "preview": "#ifndef SMARTPORT_H\n#define SMARTPORT_H\n\n#include \"common.h\"\n\n// FrSky Smartport Data Id\n\n#define ALT_FIRST_ID 0x0100  /"
  },
  {
    "path": "board/project/protocol/srxl.c",
    "chars": 5822,
    "preview": "#include \"srxl.h\"\n\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280.h\""
  },
  {
    "path": "board/project/protocol/srxl.h",
    "chars": 303,
    "preview": "#ifndef SRXL_H\n#define SRXL_H\n\n#include \"common.h\"\n#include \"xbus.h\"\n\nextern context_t context;\nextern xbus_sensor_t sen"
  },
  {
    "path": "board/project/protocol/srxl2.c",
    "chars": 8563,
    "preview": "#include \"srxl2.h\"\n\n#include <stdio.h>\n#include <stdlib.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280.h"
  },
  {
    "path": "board/project/protocol/srxl2.h",
    "chars": 1120,
    "preview": "#ifndef SRXL2_H\n#define SRXL2_H\n\n#include \"common.h\"\n#include \"xbus.h\"\n\n#define SRXL2_TIMEOUT_US 500\n#define SRXL2_HEADE"
  },
  {
    "path": "board/project/protocol/xbus.c",
    "chars": 54003,
    "preview": "#include \"xbus.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"airspeed.h\"\n#include \"bmp180.h\"\n#include \"bmp280.h\"\n#"
  },
  {
    "path": "board/project/protocol/xbus.h",
    "chars": 13010,
    "preview": "#ifndef XBUS_H\n#define XBUS_H\n\n#include \"common.h\"\n\n#define XBUS_AIRSPEED_ID 0x11\n#define XBUS_ALTIMETER_ID 0x12\n#define"
  },
  {
    "path": "board/project/sensor/CMakeLists.txt",
    "chars": 519,
    "preview": "target_sources(${PROJECT_NAME} PRIVATE\r\n    airspeed.c\r\n    esc_hw3.c\r\n    voltage.c\r\n    esc_hw4.c\r\n    esc_kontronik.c"
  },
  {
    "path": "board/project/sensor/airspeed.c",
    "chars": 2252,
    "preview": "#include \"airspeed.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"hardware/adc.h\"\n#include \"pico/stdlib.h\"\n\n/* If t"
  },
  {
    "path": "board/project/sensor/airspeed.h",
    "chars": 481,
    "preview": "#ifndef AIRSPEED_H\n#define AIRSPEED_H\n\n#include \"common.h\"\n\ntypedef struct airspeed_parameters_t {\n    uint8_t adc_num;\n"
  },
  {
    "path": "board/project/sensor/auto_offset.c",
    "chars": 818,
    "preview": "#include \"auto_offset.h\"\n\n#include <stdio.h>\n\n#include \"pico/stdlib.h\"\n\nvoid auto_offset_float_task(void *parameters) {\n"
  },
  {
    "path": "board/project/sensor/auto_offset.h",
    "chars": 458,
    "preview": "#ifndef AUTO_OFFSET_H\n#define AUTO_OFFSET_H\n\n#include \"common.h\"\n\ntypedef struct auto_offset_float_parameters_t {\n    ui"
  },
  {
    "path": "board/project/sensor/bmp180.c",
    "chars": 5703,
    "preview": "#include \"bmp180.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n#in"
  },
  {
    "path": "board/project/sensor/bmp180.h",
    "chars": 425,
    "preview": "#ifndef BMP180_H\n#define BMP180_H\n\n#include \"common.h\"\n\ntypedef struct bmp180_parameters_t {\n    float alpha_vario;\n    "
  },
  {
    "path": "board/project/sensor/bmp280.c",
    "chars": 6509,
    "preview": "#include \"bmp280.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n#in"
  },
  {
    "path": "board/project/sensor/bmp280.h",
    "chars": 464,
    "preview": "#ifndef BMP280_H\n#define BMP280_H\n\n#include \"common.h\"\n\ntypedef struct bmp280_parameters_t {\n    float alpha_vario;\n    "
  },
  {
    "path": "board/project/sensor/cell_count.c",
    "chars": 643,
    "preview": "#include \"cell_count.h\"\n\n#include <stdio.h>\n\n#include \"pico/stdlib.h\"\n\nvoid cell_count_task(void *parameters) {\n    cell"
  },
  {
    "path": "board/project/sensor/cell_count.h",
    "chars": 268,
    "preview": "#ifndef CELL_COUNT_H\n#define CELL_COUNT_H\n\n#include \"common.h\"\n\ntypedef struct cell_count_parameters_t {\n    uint delay;"
  },
  {
    "path": "board/project/sensor/current.c",
    "chars": 1886,
    "preview": "\n#include \"current.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"hardware/adc.h\"\n#include \"pico/stdlib.h\"\n\n"
  },
  {
    "path": "board/project/sensor/current.h",
    "chars": 334,
    "preview": "#ifndef CURRENT_H\n#define CURRENT_H\n\n#include \"common.h\"\n\ntypedef struct current_parameters_t {\n    uint8_t adc_num;\n   "
  },
  {
    "path": "board/project/sensor/distance.c",
    "chars": 3542,
    "preview": "#include \"distance.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"pico/stdlib.h\"\n\n#define INIT_DELAY_MS 1000\n#defin"
  },
  {
    "path": "board/project/sensor/distance.h",
    "chars": 346,
    "preview": "#ifndef DISTANCE_H\n#define DISTANCE_H\n\n#include \"common.h\"\n\ntypedef struct distance_parameters_t {\n    float *distance, "
  },
  {
    "path": "board/project/sensor/esc_apd_f.c",
    "chars": 3581,
    "preview": "#include \"esc_apd_f.h\"\n\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#include \"uart.h\"\n\n#define "
  },
  {
    "path": "board/project/sensor/esc_apd_f.h",
    "chars": 402,
    "preview": "#ifndef ESC_APD_F_H\n#define ESC_APD_F_H\n\n#include \"common.h\"\n\ntypedef struct esc_apd_f_parameters_t {\n    float rpm_mult"
  },
  {
    "path": "board/project/sensor/esc_apd_hv.c",
    "chars": 4370,
    "preview": "#include \"esc_apd_hv.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#include"
  },
  {
    "path": "board/project/sensor/esc_apd_hv.h",
    "chars": 407,
    "preview": "#ifndef ESC_APD_HV_H\n#define ESC_APD_HV_H\n\n#include \"common.h\"\n\ntypedef struct esc_apd_hv_parameters_t {\n    float rpm_m"
  },
  {
    "path": "board/project/sensor/esc_castle.c",
    "chars": 2639,
    "preview": "#include \"esc_castle.h\"\n\n#include <semphr.h>\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"hardware/clocks.h\"\n#i"
  },
  {
    "path": "board/project/sensor/esc_castle.h",
    "chars": 1114,
    "preview": "#ifndef ESC_CASTLE_H\n#define ESC_CASTLE_H\n\n#include \"castle_link.h\"\n#include \"common.h\"\n\n/* castleTelemetry:\n    index  "
  },
  {
    "path": "board/project/sensor/esc_hw3.c",
    "chars": 1940,
    "preview": "#include \"esc_hw3.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"pico/stdlib.h\"\n#include \"uart.h\"\n\n#define TIMEOUT_"
  },
  {
    "path": "board/project/sensor/esc_hw3.h",
    "chars": 247,
    "preview": "#ifndef ESC_HW3_H\n#define ESC_HW3_H\n\n#include \"common.h\"\n\ntypedef struct esc_hw3_parameters_t {\n    float multiplier;\n  "
  },
  {
    "path": "board/project/sensor/esc_hw4.c",
    "chars": 7298,
    "preview": "#include \"esc_hw4.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"cell_count.h\"\n#include \"p"
  },
  {
    "path": "board/project/sensor/esc_hw4.h",
    "chars": 607,
    "preview": "#ifndef ESC_HW4_H\n#define ESC_HW4_H\n\n#include \"common.h\"\n\ntypedef struct esc_hw4_parameters_t {\n    float rpm_multiplier"
  },
  {
    "path": "board/project/sensor/esc_hw5.c",
    "chars": 8294,
    "preview": "#include \"esc_hw5.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#inc"
  },
  {
    "path": "board/project/sensor/esc_hw5.h",
    "chars": 470,
    "preview": "#ifndef ESC_HW5_H\n#define ESC_HW5_H\n\n#include \"common.h\"\n\ntypedef struct esc_hw5_parameters_t {\n    float rpm_multiplier"
  },
  {
    "path": "board/project/sensor/esc_kontronik.c",
    "chars": 3902,
    "preview": "#include \"esc_kontronik.h\"\n\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#include \"uart.h\"\n\n#def"
  },
  {
    "path": "board/project/sensor/esc_kontronik.h",
    "chars": 480,
    "preview": "#ifndef ESC_KONTRONIK_H\n#define ESC_KONTRONIK_H\n\n#include \"common.h\"\n\ntypedef struct esc_kontronik_parameters_t {\n    fl"
  },
  {
    "path": "board/project/sensor/esc_omp_m4.c",
    "chars": 3558,
    "preview": "#include \"esc_omp_m4.h\"\n\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#include \"uart.h\"\n\n#define"
  },
  {
    "path": "board/project/sensor/esc_omp_m4.h",
    "chars": 417,
    "preview": "#ifndef ESC_OMP_M4_H\n#define ESC_OMP_M4_H\n\n#include \"common.h\"\n\ntypedef struct esc_omp_m4_parameters_t {\n    float rpm_m"
  },
  {
    "path": "board/project/sensor/esc_openyge.c",
    "chars": 12265,
    "preview": "#include \"esc_openyge.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#includ"
  },
  {
    "path": "board/project/sensor/esc_openyge.h",
    "chars": 912,
    "preview": "#ifndef ESC_OPENYGE_H\n#define ESC_OPENYGE_H\n\n#include \"common.h\"\n\ntypedef enum {\n    CRC_MODE_UNKNOWN = 0,\n    CRC_MODE_"
  },
  {
    "path": "board/project/sensor/esc_pwm.c",
    "chars": 2261,
    "preview": "#include \"esc_pwm.h\"\n\n#include <stdio.h>\n\n#include \"capture_edge.h\"\n#include \"esc_hw3.h\"\n#include \"hardware/clocks.h\"\n#i"
  },
  {
    "path": "board/project/sensor/esc_pwm.h",
    "chars": 155,
    "preview": "#ifndef ESC_PWM_H\n#define ESC_PWM_H\n\n#include \"esc_hw3.h\"\n\ntypedef esc_hw3_parameters_t esc_pwm_parameters_t;\n\nvoid esc_"
  },
  {
    "path": "board/project/sensor/esc_ztw.c",
    "chars": 3879,
    "preview": "#include \"esc_ztw.h\"\n\n#include <stdio.h>\n\n#include \"cell_count.h\"\n#include \"pico/stdlib.h\"\n#include \"uart.h\"\n\n#define ZT"
  },
  {
    "path": "board/project/sensor/esc_ztw.h",
    "chars": 416,
    "preview": "#ifndef ESC_ZTW_H\n#define ESC_ZTW_H\n\n#include \"common.h\"\n\ntypedef struct esc_ztw_parameters_t {\n    float rpm_multiplier"
  },
  {
    "path": "board/project/sensor/fuel_meter.c",
    "chars": 1828,
    "preview": "#include \"fuel_meter.h\"\n\n#include <stdio.h>\n\n#include \"capture_edge.h\"\n#include \"hardware/clocks.h\"\n#include \"hardware/i"
  },
  {
    "path": "board/project/sensor/fuel_meter.h",
    "chars": 328,
    "preview": "#ifndef FUEL_METER_H\n#define FUEL_METER_H\n\n#include \"common.h\"\n\ntypedef struct fuel_meter_parameters_t {\n    float ml_pe"
  },
  {
    "path": "board/project/sensor/gpio.c",
    "chars": 718,
    "preview": "#include \"gpio.h\"\n\n#include <stdio.h>\n\n#include \"pico/stdlib.h\"\n\n#define GPIO_MASK (1 << 17)\n\nvoid gpio_task(void *param"
  },
  {
    "path": "board/project/sensor/gpio.h",
    "chars": 252,
    "preview": "#ifndef GPIO_SENSOR_H\n#define GPIO_SENSOR_H\n\n#include \"common.h\"\n\ntypedef struct gpio_parameters_t {\n    uint8_t mask;\n "
  },
  {
    "path": "board/project/sensor/gps.c",
    "chars": 20055,
    "preview": "#include \"gps.h\"\n\n#include <math.h>\n#include <stdio.h>\n#include <string.h>\n\n#include \"distance.h\"\n#include \"pico/stdlib."
  },
  {
    "path": "board/project/sensor/gps.h",
    "chars": 493,
    "preview": "#ifndef GPS_H\n#define GPS_H\n\n#include \"common.h\"\n\ntypedef struct gps_parameters_t {\n    gps_protocol_t protocol;\n    uin"
  },
  {
    "path": "board/project/sensor/ina3221.c",
    "chars": 3770,
    "preview": "#include \"ina3221.h\"\n\n#include <stdio.h>\n\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n\n//  REGISTERS\n#define INA3"
  },
  {
    "path": "board/project/sensor/ina3221.h",
    "chars": 332,
    "preview": "#ifndef INA3221_H\n#define INA3221_H\n\n#include \"common.h\"\n\ntypedef struct ina3221_parameters_t {\n    uint8_t i2c_address;"
  },
  {
    "path": "board/project/sensor/mpu6050.c",
    "chars": 9973,
    "preview": "#include \"mpu6050.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n\n#define "
  },
  {
    "path": "board/project/sensor/mpu6050.h",
    "chars": 353,
    "preview": "#ifndef MPU6050_H\n#define MPU6050_H\n\n#include \"common.h\"\n\ntypedef struct mpu6050_parameters_t {\n    float alpha_gyro;\n  "
  },
  {
    "path": "board/project/sensor/ms5611.c",
    "chars": 6134,
    "preview": "#include \"ms5611.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n#in"
  },
  {
    "path": "board/project/sensor/ms5611.h",
    "chars": 408,
    "preview": "#ifndef MS5611_H\n#define MS5611_H\n\n#include \"common.h\"\n\ntypedef struct ms5611_parameters_t {\n    float alpha_vario;\n    "
  },
  {
    "path": "board/project/sensor/ntc.c",
    "chars": 1247,
    "preview": "#include \"ntc.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"hardware/adc.h\"\n\n// Thermistors (NTC 100k, R1 10k)\n#de"
  },
  {
    "path": "board/project/sensor/ntc.h",
    "chars": 264,
    "preview": "#ifndef NTC_H\n#define NTC_H\n\n#include \"common.h\"\n\ntypedef struct ntc_parameters_t {\n    uint8_t adc_num;\n    uint8_t rat"
  },
  {
    "path": "board/project/sensor/pwm_out.c",
    "chars": 991,
    "preview": "#include \"pwm_out.h\"\n\n#include <stdio.h>\n\n#include \"hardware/clocks.h\"\n#include \"hardware/pwm.h\"\n\nvoid pwm_out_task(void"
  },
  {
    "path": "board/project/sensor/pwm_out.h",
    "chars": 130,
    "preview": "#ifndef PWM_OUT_H\n#define PWM_OUT_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid pwm_out_task(void *parameters)"
  },
  {
    "path": "board/project/sensor/smart_esc.c",
    "chars": 17367,
    "preview": "#include \"smart_esc.h\"\n\n#include <stdio.h>\n\n#include \"auto_offset.h\"\n#include \"capture_edge.h\"\n#include \"cell_count.h\"\n#"
  },
  {
    "path": "board/project/sensor/smart_esc.h",
    "chars": 748,
    "preview": "#ifndef SMART_ESC_H\n#define SMART_ESC_H\n\n#include \"common.h\"\n\ntypedef struct smart_esc_parameters_t {\n    bool calc_cons"
  },
  {
    "path": "board/project/sensor/voltage.c",
    "chars": 781,
    "preview": "#include \"voltage.h\"\n\n#include <stdio.h>\n\n#include \"hardware/adc.h\"\n#include \"pico/stdlib.h\"\n\nvoid voltage_task(void *pa"
  },
  {
    "path": "board/project/sensor/voltage.h",
    "chars": 280,
    "preview": "#ifndef VOLTAGE_H\n#define VOLTAGE_H\n\n#include \"common.h\"\n\ntypedef struct voltage_parameters_t {\n    uint8_t adc_num;\n   "
  },
  {
    "path": "board/project/sensor/vspeed.c",
    "chars": 766,
    "preview": "#include \"vspeed.h\"\n\n#include <stdio.h>\n\n#include \"common.h\"\n#include \"pico/stdlib.h\"\n\n#define VSPEED_INIT_DELAY_MS 5000"
  },
  {
    "path": "board/project/sensor/vspeed.h",
    "chars": 236,
    "preview": "#ifndef VSPEED_H\n#define VSPEED_H\n\n#include \"common.h\"\n\ntypedef struct vspeed_parameters_t {\n    uint interval;\n    floa"
  },
  {
    "path": "board/project/sensor/xgzp68xxd.c",
    "chars": 2276,
    "preview": "#include \"xgzp68xxd.h\"\n\n#include <stdio.h>\n\n#include \"hardware/i2c.h\"\n#include \"pico/stdlib.h\"\n#include \"stdlib.h\"\n\n#def"
  },
  {
    "path": "board/project/sensor/xgzp68xxd.h",
    "chars": 253,
    "preview": "#ifndef XGZP68XXD_H\n#define XGZP68XXD_H\n\n#include \"common.h\"\n\ntypedef struct xgzp68xxd_parameters_t {\n    uint16_t k;\n  "
  },
  {
    "path": "board/project/serial_monitor.c",
    "chars": 2783,
    "preview": "#include \"serial_monitor.h\"\n\n#include <math.h>\n#include <stdio.h>\n\n#include \"config.h\"\n#include \"pico/stdlib.h\"\n#include"
  },
  {
    "path": "board/project/serial_monitor.h",
    "chars": 150,
    "preview": "#ifndef SERIAL_MONITOR_H\n#define SERIAL_MONITOR_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid serial_monitor_t"
  },
  {
    "path": "board/project/sim_rx.c",
    "chars": 15975,
    "preview": "#include \"sim_rx.h\"\n\n#include <stdio.h>\n\n#include \"config.h\"\n#include \"hitec.h\"\n#include \"uart.h\"\n#include \"xbus.h\"\n\n#de"
  },
  {
    "path": "board/project/sim_rx.h",
    "chars": 218,
    "preview": "#ifndef SIM_RX_H\n#define SIM_RX_H\n\n#include \"common.h\"\n\nextern context_t context;\n\ntypedef struct sim_rx_parameters_t {\n"
  },
  {
    "path": "board/project/uart.c",
    "chars": 9023,
    "preview": "#include \"uart.h\"\n\n#include <stdio.h>\n\n#include \"hardware/irq.h\"\n#include \"hardware/uart.h\"\n\n#define UART0_BUFFER_SIZE 5"
  },
  {
    "path": "board/project/uart.h",
    "chars": 940,
    "preview": "#ifndef UART_H\n#define UART_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid uart0_begin(uint baudrate, uint gpio"
  },
  {
    "path": "board/project/uart_pio.c",
    "chars": 3766,
    "preview": "#include \"uart_pio.h\"\n\n#include <stdio.h>\n\n#include \"common.h\"\n#include \"hardware/irq.h\"\n#include \"hardware/pio.h\"\n\nstat"
  },
  {
    "path": "board/project/uart_pio.h",
    "chars": 639,
    "preview": "#ifndef UART_PIO_H\n#define UART_PIO_H\n\n#include \"common.h\"\n#include \"uart_rx.h\"\n#include \"uart_tx.h\"\n\n#define UART_PIO_B"
  },
  {
    "path": "board/project/usb.c",
    "chars": 3682,
    "preview": "#include \"usb.h\"\n\n#include <queue.h>\n#include <stdio.h>\n\n#include \"config.h\"\n#include \"pico/stdlib.h\"\n#include \"string.h"
  },
  {
    "path": "board/project/usb.h",
    "chars": 129,
    "preview": "#ifndef USB_H\n#define USB_H\n\n#include \"common.h\"\n\nextern context_t context;\n\nvoid usb_task();\n\nextern context_t context;"
  },
  {
    "path": "case/MSRC_case_zero-Lower case.stl",
    "chars": 131,
    "preview": "version https://git-lfs.github.com/spec/v1\noid sha256:706d1712a05c26d363e756b3c37a33e08091c530aa5a3a4d4ae283afff7a6ff0\ns"
  },
  {
    "path": "case/MSRC_case_zero-Upper case.stl",
    "chars": 131,
    "preview": "version https://git-lfs.github.com/spec/v1\noid sha256:9e29e04059e759b96d55ae8b1698df50249703a28a3ffe5457d4ccf6f9c29b4c\ns"
  },
  {
    "path": "case/MSRC_case_zero.3mf",
    "chars": 130,
    "preview": "version https://git-lfs.github.com/spec/v1\noid sha256:df72a711ca0eb78f81886c5d42da3f04503d07448e117a83678408008134164a\ns"
  },
  {
    "path": "case/MSRC_case_zero.FCStd",
    "chars": 132,
    "preview": "version https://git-lfs.github.com/spec/v1\noid sha256:f958637abcdd52ebfe8e2f99acd9b631e951af492a2a80fb3f67ae941ddf843e\ns"
  },
  {
    "path": "case/MSRC_case_zero_PLA_1h27m.gcode",
    "chars": 132,
    "preview": "version https://git-lfs.github.com/spec/v1\noid sha256:11042343aad94bb6fef96a9717a1ab6ead31a9674e0f2fc6b89eadc720c977dd\ns"
  },
  {
    "path": "include/shared.h",
    "chars": 7691,
    "preview": "#ifndef SHARED_H\n#define SHARED_H\n\n#include <stdint.h>\n\n#ifdef __cplusplus\n\ntypedef enum rx_protocol_t : uint8_t {\n    R"
  },
  {
    "path": "lua/MSRC.lua",
    "chars": 19174,
    "preview": "local toolName = \"TNS|MSRC config|TNE\"\n\nlocal scriptVersion = \"v1.4\"\n\nlocal statusEnum = {\n\tstart = 1,\n\tgetConfig = 2,\n\t"
  },
  {
    "path": "msrc_gui/appdir/msrc.desktop",
    "chars": 130,
    "preview": "[Desktop Entry]\nType=Application\nName=MSRC\nExec=msrc_gui %F\nIcon=msrc\nComment=Sensors for RC\nTerminal=false\nCategories ="
  },
  {
    "path": "msrc_gui/circuitdialog.cpp",
    "chars": 1502,
    "preview": "#include \"circuitdialog.h\"\n#include \"ui_circuitdialog.h\"\n\nCircuitDialog::CircuitDialog(QWidget *parent) :\n    QDialog(pa"
  },
  {
    "path": "msrc_gui/circuitdialog.h",
    "chars": 559,
    "preview": "#ifndef CIRCUITDIALOG_H\n#define CIRCUITDIALOG_H\n\n#include <QDialog>\n#include <QLabel>\n#include <QDebug>\n#include \"mainwi"
  },
  {
    "path": "msrc_gui/circuitdialog.ui",
    "chars": 1910,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>CircuitDialog</class>\n <widget class=\"QDialog\" name=\"C"
  },
  {
    "path": "msrc_gui/main.cpp",
    "chars": 173,
    "preview": "#include \"mainwindow.h\"\n\n#include <QApplication>\n\nint main(int argc, char *argv[])\n{ \n    QApplication a(argc, argv);\n  "
  },
  {
    "path": "msrc_gui/mainwindow.cpp",
    "chars": 52101,
    "preview": "#include \"mainwindow.h\"\n\n#include \"circuitdialog.h\"\n#include \"qobject.h\"\n#include \"ui_mainwindow.h\"\n\nMainWindow::MainWi"
  },
  {
    "path": "msrc_gui/mainwindow.h",
    "chars": 2432,
    "preview": "#ifndef MAINWINDOW_H\n#define MAINWINDOW_H\n\n#define CONFIG_VERSION 2\n\n#include <QDebug>\n#include <QFileDialog>\n#include <"
  },
  {
    "path": "msrc_gui/mainwindow.ui",
    "chars": 78266,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<ui version=\"4.0\">\n <class>MainWindow</class>\n <widget class=\"QMainWindow\" name=\""
  },
  {
    "path": "msrc_gui/msrc_gui.pro",
    "chars": 949,
    "preview": "QT       += core gui serialport\n\ngreaterThan(QT_MAJOR_VERSION, 4): QT += widgets\n\nsystem(git describe --tags > VERSION)\n"
  },
  {
    "path": "msrc_gui/resources.qrc",
    "chars": 997,
    "preview": "<RCC>\n    <qresource prefix=\"/\">\n        <file>res/castle_rp2040_zero.png</file>\n        <file>res/gps_rp2040_zero.png</"
  },
  {
    "path": "msrc_gui_web/README.md",
    "chars": 11239,
    "preview": "# MSRC Link Web\n\nA web-based alternative for the Qt desktop configurator (`msrc_gui/`), built with vanilla JavaScript, t"
  },
  {
    "path": "msrc_gui_web/css/style.css",
    "chars": 6787,
    "preview": ":root {\n    --bg-primary: #1a1a2e;\n    --bg-secondary: #16213e;\n    --bg-card: #0f3460;\n    --bg-input: #1a1a3e;\n    --t"
  },
  {
    "path": "msrc_gui_web/index.html",
    "chars": 30055,
    "preview": "<!DOCTYPE html>\n<html lang=\"en\">\n<head>\n    <meta charset=\"UTF-8\">\n    <meta name=\"viewport\" content=\"width=device-width"
  },
  {
    "path": "msrc_gui_web/js/app.js",
    "chars": 7643,
    "preview": "/**\n * app.js — Main application entry point.\n *          Orchestrates serial communication, UI mapping, circuit diagram"
  },
  {
    "path": "msrc_gui_web/js/circuit.js",
    "chars": 5192,
    "preview": "/**\n * circuit.js — Canvas-based circuit diagram that composites PNG overlay images,\n *              matching the Qt gen"
  },
  {
    "path": "msrc_gui_web/js/config_struct.js",
    "chars": 12831,
    "preview": "/**\n * config_struct.js — Binary serialization of config_t matching the C struct layout in include/shared.h.\n *\n * The f"
  },
  {
    "path": "msrc_gui_web/js/serial.js",
    "chars": 13699,
    "preview": "/**\n * serial.js — Web Serial API communication with MSRC board.\n *\n * Protocol: all messages start with header byte 0x3"
  },
  {
    "path": "msrc_gui_web/js/ui.js",
    "chars": 21578,
    "preview": "/**\n * ui.js — Bidirectional mapping between config_t and DOM widgets.\n *         Also handles protocol-dependent widget"
  },
  {
    "path": "msrc_gui_web/js/version.js",
    "chars": 29,
    "preview": "const APP_VERSION = '1.0.1';\n"
  },
  {
    "path": "msrc_gui_web/manifest.json",
    "chars": 607,
    "preview": "{\n    \"name\": \"MSRC Link Web\",\n    \"short_name\": \"MSRC Link\",\n    \"description\": \"Web-based configuration tool for MSRC "
  },
  {
    "path": "msrc_gui_web/sw.js",
    "chars": 1728,
    "preview": "/**\n * sw.js — Service Worker for offline PWA support.\n * Caches all app assets on install, serves from cache first.\n */"
  },
  {
    "path": "msrc_gui_web/test/layout_test.html",
    "chars": 1485,
    "preview": "<!DOCTYPE html>\n<html><head><meta charset=\"utf-8\"><title>Config Layout Test</title></head>\n<body><pre id=\"out\"></pre>\n<s"
  },
  {
    "path": "msrc_gui_web/test/verify_layout.js",
    "chars": 2546,
    "preview": "// Test: verifies JS config_t layout matches C++ offsets.\n// Run: docker run --rm -v $(pwd):/app -w /app node:20-alpine "
  }
]

About this extraction

This page contains the full source code of the dgatf/msrc GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 189 files (1.4 MB), approximately 370.9k tokens, and a symbol index with 643 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.

Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.

Copied to clipboard!