feat: adopt ELRS USB CRSF frame format, add skeleton modules

Switch CRC from CCITT (0x07) to DVB-S2 (0xD5) to match ELRS.
Adopt ELRS USB frame format: [addr][length][type][payload][crc].
Update frame type constants to match current ELRS protocol values.

New skeleton modules (stub implementations with TODO comments):
  - crsf_telemetry.h/.c: telemetry decoders (GPS, battery, link..)
  - crsf_stream.h/.c: incremental streaming frame reader
  - crsf_param.h/.c: parameter protocol (read/write/set_power)

Retained old frame format as *_legacy functions for backward
compatibility with existing telemetry tool and tests.

Add cel_serial_find_elrs_port() and cel_serial_open_probe()
stubs to serial module for port auto-detection and baud probing.
This commit is contained in:
2026-06-14 20:47:56 +02:00
parent c42ec407da
commit df3d399610
16 changed files with 919 additions and 156 deletions
+18 -16
View File
@@ -131,19 +131,22 @@ Added unit tests for empty, single-byte, and known-value cases.
```text
celrs/
crsf.h / crsf.c CRSF protocol: CRC8, frame parse/build
serial.h / serial.c Serial port abstraction (Win/POSIX stubs)
logger.h / logger.c Level-filtering logger
log_write.h/.c stdout log sink
crsf.h / crsf.c CRSF protocol: CRC8/DVB-S2, frame build/parse
crsf_telemetry.h/.c Telemetry frame decoders (GPS, battery, link..)
crsf_stream.h/.c Incremental streaming frame reader
crsf_param.h/.c Parameter protocol (read/write/set_power)
serial.h / serial.c Serial port abstraction (Win/POSIX)
logger.h / logger.c Level-filtering logger
log_write.h/.c stdout log sink
tools/
telemetry.c Telemetry read tool
telemetry.c Telemetry read tool
tests/
test_crsf.c CRSF CRC, parse, build tests
test_serial.c Serial open/close/stub tests
test_logger.c Logger level-filtering tests
test_crsf.c CRSF CRC, parse, build tests
test_serial.c Serial open/close/stub tests
test_logger.c Logger level-filtering tests
deps/
FindUnity.cmake Fetches Unity v2.6.1 via ZIP
FindCMock.cmake Fetches CMock v2.6.0 via ZIP
FindUnity.cmake Fetches Unity v2.6.1 via ZIP
FindCMock.cmake Fetches CMock v2.6.0 via ZIP
```
## TDD Workflow
@@ -239,9 +242,8 @@ The project supports Windows, Linux, macOS, Emscripten, and Android via
CRSF is the Crossfire Serial Protocol used by ELRS. Key points:
- Frame header is always `0xC8`
- CRC8-CCITT with polynomial `0x07`, init `0x00`
- CRC is computed over: destination + source + type + size + payload
- Standard baud rate for ELRS CRSF is 400000 bps
- TX modules expose CRSF over USB serial (appears as COM port on Windows,
/dev/ttyUSB* on Linux)
- Frame format: [addr][length][type][payload...][crc]
- CRC8/DVB-S2 with polynomial `0xD5`, init `0x00`
- CRC is computed over: type + payload
- Address byte varies: `0xC8` (host), `0xEE` (module), `0xEF` (lua)
- Standard baud rate for ELRS CRSF is 400000 bps (probe 921600 first)
+36 -29
View File
@@ -74,19 +74,22 @@ mock files are excluded. Requires GCC or Clang with gcov support, and
```
celrs/
crsf.h / crsf.c CRSF protocol: CRC8, frame parse/build
serial.h / serial.c Serial port abstraction (Win/POSIX)
logger.h / logger.c Level-filtering logger
log_write.h/.c stdout log sink
crsf.h / crsf.c CRSF protocol: CRC8/DVB-S2, frame build/parse
crsf_telemetry.h/.c Telemetry frame decoders (GPS, battery, link..)
crsf_stream.h/.c Incremental streaming frame reader
crsf_param.h/.c Parameter protocol (read/write/set_power)
serial.h / serial.c Serial port abstraction (Win/POSIX)
logger.h / logger.c Level-filtering logger
log_write.h/.c stdout log sink
tools/
telemetry.c Telemetry read tool
telemetry.c Telemetry read tool
tests/
test_crsf.c CRSF CRC, parse, build tests
test_serial.c Serial open/close/stub tests
test_logger.c Logger level-filtering tests
test_crsf.c CRSF CRC, parse, build tests
test_serial.c Serial open/close/stub tests
test_logger.c Logger level-filtering tests
deps/
FindUnity.cmake Fetches Unity v2.6.1 via ZIP
FindCMock.cmake Fetches CMock v2.6.0 via ZIP
FindUnity.cmake Fetches Unity v2.6.1 via ZIP
FindCMock.cmake Fetches CMock v2.6.0 via ZIP
```
## CRSF Protocol
@@ -94,22 +97,20 @@ deps/
CRSF (Crossfire Serial Protocol) is the serial protocol used by ELRS for
communication between ground station and TX/RX modules.
### Frame format
### Frame format (ELRS USB CRSF)
```
+------+------+------+------+-------+-------+
| 0xC8 | dest | src | type | size | ... | CRC |
+------+------+------+------+-------+-------+
1 byte 1B 1B 1B 1B N B 1 byte
+--------+----------+--------+----------+-----+
| addr | length | type | payload | CRC |
+--------+----------+--------+----------+-----+
1 byte 1 byte 1 byte N bytes 1B
```
- **Header:** Always `0xC8`
- **Destination:** Target device address
- **Source:** Sender device address
- **Type:** Frame type (heartbeat, RC channels, telemetry, etc.)
- **Size:** Payload length in bytes
- **Address:** Frame sync byte (`0xC8` for host, `0xEE` for module, etc.)
- **Length:** Total bytes after this field (type + payload + CRC)
- **Type:** Frame type (RC channels, telemetry, parameter, etc.)
- **Payload:** Frame-specific data
- **CRC:** CRC8-CCITT over dest+src+type+size+payload
- **CRC:** CRC8/DVB-S2 (poly `0xD5`) over type + payload
### Common device addresses
@@ -118,17 +119,23 @@ communication between ground station and TX/RX modules.
| 0x00 | FC Broadcast |
| 0x10 | Flight Controller |
| 0x80 | TBS Ground Station |
| 0xEA | Custom Module |
| 0xDD | RC Device |
| 0xEA | Custom Module (Radio) |
| 0xEE | ELRS TX Module |
| 0xEF | ELRS Lua (host script) |
### Common frame types
| Type | Name |
| ------ | --------------------------- |
| 0x01 | RC Channels Packed |
| 0x02 | Packet Link Telemetry |
| 0x03 | Heartbeat |
| 0x08 | Device Info |
| 0x09 | Parameter List |
| 0x17 | MSP Read |
| 0x18 | MSP Write |
| 0x02 | GPS |
| 0x08 | Battery |
| 0x0B | Heartbeat |
| 0x14 | Link Stats |
| 0x16 | RC Channels |
| 0x28 | Device Ping |
| 0x29 | Device Info |
| 0x2B | Parameter Entry |
| 0x2C | Parameter Read |
| 0x2D | Parameter Write |
| 0x2E | ELRS Status |
+3 -1
View File
@@ -1,6 +1,8 @@
add_library(celrs_crsf STATIC crsf.c)
add_library(celrs_crsf STATIC crsf.c crsf_telemetry.c crsf_stream.c
crsf_param.c)
target_include_directories(celrs_crsf PUBLIC "${CMAKE_SOURCE_DIR}")
target_compile_features(celrs_crsf PRIVATE c_std_23)
target_link_libraries(celrs_crsf PUBLIC celrs_serial)
# Platform-agnostic serial logic — calls cel_serial_platform_*();
# symbol resolved by celrs_serial_platform (or a mock in tests)
+136 -26
View File
@@ -1,20 +1,142 @@
#include "celrs/crsf.h"
#include <string.h>
/* CRC8-CCITT with polynomial 0x07, init 0x00 (used by CRSF/ELRS) */
/* --------------------------------------------------------------------------- */
/* CRC8/DVB-S2 lookup table (poly 0xD5) */
/* --------------------------------------------------------------------------- */
static uint8_t s_crc8_table[256];
static int s_crc8_init = 0;
static void crc8_build_table(void) {
for (int i = 0; i < 256; i++) {
uint8_t crc = (uint8_t)i;
for (int j = 0; j < 8; j++) {
crc = (crc & 0x80)
? ((crc << 1) ^ 0xD5)
: (crc << 1);
}
s_crc8_table[i] = crc;
}
s_crc8_init = 1;
}
uint8_t cel_crsf_crc(uint8_t const* data, size_t len) {
if (!s_crc8_init) crc8_build_table();
uint8_t crc = 0x00;
for (size_t i = 0; i < len; i++) {
crc ^= data[i];
for (int j = 0; j < 8; j++) {
crc = (crc & 0x80) ? (crc << 1) ^ 0x07 : (crc << 1);
}
crc = s_crc8_table[crc ^ data[i]];
}
return crc;
}
int cel_crsf_frame_validate(cel_crsf_frame const* frame) {
/* Rebuild the data that was CRC'd: dest + src + type + size + payload */
/* --------------------------------------------------------------------------- */
/* Frame builders */
/* --------------------------------------------------------------------------- */
size_t cel_crsf_build_rc_frame(uint8_t* dst, int16_t const channels[16]) {
/* TODO: pack 16 channels (11-bit each) into 22 bytes.
* Frame layout: [0xC8][length][0x16][packed_22B][crc]
* length = 1 (type) + 22 (payload) + 1 (crc) = 24
* CRC over type + payload.
* Clamp each channel to [CEL_CRSF_CH_MIN, CEL_CRSF_CH_MAX] first.
* Return 2 + length = 26 bytes written. */
(void)dst;
(void)channels;
return 0;
}
size_t cel_crsf_build_ping_frame(uint8_t* dst) {
/* TODO: build device ping frame (type 0x28).
* Frame layout: [0xEE][length][0x28][0x00][0xEA][crc]
* Payload: dest=0x00 (broadcast), src=0xEA (radio transmitter)
* length = 1 + 2 + 1 = 4, total = 6 bytes. */
(void)dst;
return 0;
}
size_t cel_crsf_build_param_read_frame(uint8_t* dst, uint8_t index,
uint8_t chunk) {
/* TODO: build parameter read frame (type 0x2C).
* Frame layout: [0xEE][length][0x2C][0xEE][0xEF][index][chunk][crc]
* Payload: dest=0xEE (module), src=0xEF (lua), index, chunk
* length = 1 + 4 + 1 = 6, total = 8 bytes. */
(void)dst;
(void)index;
(void)chunk;
return 0;
}
size_t cel_crsf_build_param_write_frame(uint8_t* dst, uint8_t index,
uint8_t value) {
/* TODO: build parameter write frame (type 0x2D).
* Frame layout: [0xEE][length][0x2D][0xEE][0xEF][index][value][crc]
* Payload: dest=0xEE (module), src=0xEF (lua), index, value
* length = 1 + 4 + 1 = 6, total = 8 bytes. */
(void)dst;
(void)index;
(void)value;
return 0;
}
/* --------------------------------------------------------------------------- */
/* Frame parser */
/* --------------------------------------------------------------------------- */
int cel_crsf_frame_parse(cel_crsf_frame* frame, uint8_t const* buf,
size_t len) {
/* TODO: parse ELRS-format frame [addr][length][type][payload...][crc].
* Validate:
* - buf has at least 4 bytes (addr + length + type + crc minimum)
* - total frame = 2 (addr+length) + length bytes
* - CRC over buf[2..2+length-1] matches buf[2+length-1]
* Copy type and payload into frame struct. */
(void)frame;
(void)buf;
(void)len;
return -1;
}
/* --------------------------------------------------------------------------- */
/* Channel helpers */
/* --------------------------------------------------------------------------- */
int16_t cel_crsf_channel_clamp(int16_t value) {
if (value < CEL_CRSF_CH_MIN) return CEL_CRSF_CH_MIN;
if (value > CEL_CRSF_CH_MAX) return CEL_CRSF_CH_MAX;
return value;
}
int16_t cel_crsf_channel_us_to_val(uint16_t us) {
/* TODO: convert microseconds to 11-bit channel value.
* Linear mapping: 988us -> 172, 2012us -> 1811.
* value = (us - 988) * (1811 - 172) / (2012 - 988) + 172
* Clamp result to [CEL_CRSF_CH_MIN, CEL_CRSF_CH_MAX]. */
(void)us;
return CEL_CRSF_CH_MID;
}
uint16_t cel_crsf_channel_val_to_us(int16_t value) {
/* TODO: convert 11-bit channel value to microseconds.
* Linear mapping: 172 -> 988us, 1811 -> 2012us.
* us = (value - 172) * (2012 - 988) / (1811 - 172) + 988 */
(void)value;
return 1500;
}
void cel_crsf_channel_default(int16_t channels[16]) {
/* TODO: fill with safe/disarmed values.
* CH1-Roll, CH2-Pitch, CH4-Yaw = CEL_CRSF_CH_MID (centered)
* CH3-Throttle = CEL_CRSF_CH_MIN (zero)
* CH5..CH16 (AUX) = CEL_CRSF_CH_MIN (off) */
(void)channels;
}
/* --------------------------------------------------------------------------- */
/* Deprecated (old frame format) */
/* --------------------------------------------------------------------------- */
int cel_crsf_frame_validate(cel_crsf_frame_legacy const* frame) {
uint8_t data[260];
size_t offset = 0;
data[offset++] = frame->destination;
@@ -23,52 +145,40 @@ int cel_crsf_frame_validate(cel_crsf_frame const* frame) {
data[offset++] = frame->size;
memcpy(data + offset, frame->payload, frame->size);
offset += frame->size;
uint8_t calc_crc = cel_crsf_crc(data, offset);
return calc_crc == frame->crc ? 0 : -1;
}
int cel_crsf_frame_parse(cel_crsf_frame* frame, uint8_t const* buf, size_t len) {
int cel_crsf_frame_parse_legacy(cel_crsf_frame_legacy* frame, uint8_t const* buf,
size_t len) {
if (frame == NULL || buf == NULL) return -1;
/* Minimum: header(1) + dest(1) + src(1) + type(1) + size(1) = 5 bytes */
if (len < 5) return -1;
/* Verify header */
if (buf[0] != CEL_CRSF_FRAME_HEADER) return -1;
frame->destination = buf[1];
frame->source = buf[2];
frame->type = buf[3];
frame->size = buf[4];
uint8_t size = buf[4];
/* Total: header(1) + dest(1) + src(1) + type(1) + size(1) + payload(N) + crc(1) */
size_t total = 6 + size;
if (len < total) return -1;
memcpy(frame->payload, buf + 5, size);
frame->crc = buf[5 + size];
return cel_crsf_frame_validate(frame);
}
size_t cel_crsf_frame_build(uint8_t* dst, uint8_t destination, uint8_t source,
uint8_t type, uint8_t const* payload, uint8_t size) {
size_t cel_crsf_frame_build_legacy(uint8_t* dst, uint8_t destination,
uint8_t source, uint8_t type,
uint8_t const* payload, uint8_t size) {
if (dst == NULL) return 0;
dst[0] = CEL_CRSF_FRAME_HEADER;
dst[1] = destination;
dst[2] = source;
dst[3] = type;
dst[4] = size;
if (payload != NULL && size > 0) {
memcpy(dst + 5, payload, size);
}
/* CRC over dest + src + type + size + payload */
uint8_t crc = cel_crsf_crc(dst + 1, 3 + 1 + size);
dst[5 + size] = crc;
return 1 + 3 + 1 + size + 1; /* header + 3 fields + size byte + payload + crc */
}
return 1 + 3 + 1 + size + 1;
}
+104 -39
View File
@@ -13,32 +13,106 @@
#define CEL_CRSF_ADDRESS_RC_DEVICE 0xDD
#define CEL_CRSF_ADDRESS_GPS 0xEC
#define CEL_CRSF_ADDRESS_FLIGHT_CONTROLLER 0xED
#define CEL_CRSF_ADDRESS_MODULE 0xEE
#define CEL_CRSF_ADDRESS_LUA 0xEF
/* CRSF frame types */
/* CRSF frame types (ELRS) */
typedef enum {
CEL_CRSF_FRAMETYPE_PACKET_LINK_TELEMETRY = 0x02,
CEL_CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x01,
CEL_CRSF_FRAMETYPE_GPS = 0x02,
CEL_CRSF_FRAMETYPE_HEARTBEAT = 0x03,
CEL_CRSF_FRAMETYPE_VERSION = 0x04,
CEL_CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x05,
CEL_CRSF_FRAMETYPE_PARAMETER_READ = 0x06,
CEL_CRSF_FRAMETYPE_PARAMETER_WRITE = 0x07,
CEL_CRSF_FRAMETYPE_DEVICE_INFO = 0x08,
CEL_CRSF_FRAMETYPE_PARAMETER_LIST = 0x09,
CEL_CRSF_FRAMETYPE_RC_CHANNELS_RAW = 0x16,
CEL_CRSF_FRAMETYPE_MSP_READ = 0x17,
CEL_CRSF_FRAMETYPE_MSP_WRITE = 0x18,
CEL_CRSF_FRAMETYPE_CURR_VOLTAGE_TEMP = 0x1E,
CEL_CRSF_FRAMETYPE_BATTERY_SENSOR = 0x1F,
CEL_CRSF_FRAMETYPE_COMPRESSED_SENSORS = 0x28,
CEL_CRSF_FRAMETYPE_ARM = 0x0D,
CEL_CRSF_FRAMETYPE_SETTING = 0x9E,
CEL_CRSF_FRAMETYPE_SUPERBOX = 0xA0,
CEL_CRSF_FRAMETYPE_DEVICE_SUPERBOX = 0xA1,
} cel_crsf_frame_type;
CEL_CRSF_TYPE_RC_CHANNELS_PACKED = 0x01,
CEL_CRSF_TYPE_GPS = 0x02,
CEL_CRSF_TYPE_VARIO = 0x07,
CEL_CRSF_TYPE_BATTERY = 0x08,
CEL_CRSF_TYPE_BARO_ALT = 0x09,
CEL_CRSF_TYPE_AIRSPEED = 0x0A,
CEL_CRSF_TYPE_HEARTBEAT = 0x0B,
CEL_CRSF_TYPE_RPM = 0x0C,
CEL_CRSF_TYPE_TEMP = 0x0D,
CEL_CRSF_TYPE_VOLTAGES = 0x0E,
CEL_CRSF_TYPE_ESC_SENSOR = 0x10,
CEL_CRSF_TYPE_LINK_STATS = 0x14,
CEL_CRSF_TYPE_RC_CHANNELS = 0x16,
CEL_CRSF_TYPE_ATTITUDE = 0x1E,
CEL_CRSF_TYPE_FLIGHT_MODE = 0x21,
CEL_CRSF_TYPE_DEVICE_PING = 0x28,
CEL_CRSF_TYPE_DEVICE_INFO = 0x29,
CEL_CRSF_TYPE_PARAM_ENTRY = 0x2B,
CEL_CRSF_TYPE_PARAM_READ = 0x2C,
CEL_CRSF_TYPE_PARAM_WRITE = 0x2D,
CEL_CRSF_TYPE_ELRS_STATUS = 0x2E,
} cel_crsf_type;
/* Parsed CRSF frame */
/* ELRS parameter types */
typedef enum {
CEL_PARAM_UINT8 = 0,
CEL_PARAM_INT8 = 1,
CEL_PARAM_UINT16 = 2,
CEL_PARAM_INT16 = 3,
CEL_PARAM_UINT32 = 4,
CEL_PARAM_INT32 = 5,
CEL_PARAM_FLOAT = 8,
CEL_PARAM_TEXT_SELECT = 9,
CEL_PARAM_STRING = 10,
CEL_PARAM_FOLDER = 11,
CEL_PARAM_INFO = 12,
CEL_PARAM_COMMAND = 13,
} cel_param_type;
/* Channel value mapping (11-bit) */
#define CEL_CRSF_CH_MIN 172 /* 988 us */
#define CEL_CRSF_CH_MID 992 /* 1500 us */
#define CEL_CRSF_CH_MAX 1811 /* 2012 us */
/* Parsed CRSF frame (ELRS USB format: [addr][length][type][payload][crc]) */
typedef struct {
uint8_t addr;
uint8_t length;
uint8_t type;
uint8_t payload[255];
uint8_t payload_len;
uint8_t crc;
} cel_crsf_frame;
/* CRC8/DVB-S2 (poly 0xD5, init 0x00) */
uint8_t cel_crsf_crc(uint8_t const* data, size_t len);
/* Build an RC channels frame (16 channels, 11-bit each).
Returns total bytes written into dst (min 28 bytes needed). */
size_t cel_crsf_build_rc_frame(uint8_t* dst, int16_t const channels[16]);
/* Build a device ping frame. Returns bytes written (min 7 bytes needed). */
size_t cel_crsf_build_ping_frame(uint8_t* dst);
/* Build a parameter read frame. Returns bytes written (min 9 bytes needed). */
size_t cel_crsf_build_param_read_frame(uint8_t* dst, uint8_t index,
uint8_t chunk);
/* Build a parameter write frame. Returns bytes written (min 9 bytes needed). */
size_t cel_crsf_build_param_write_frame(uint8_t* dst, uint8_t index,
uint8_t value);
/* Parse a single CRSF frame from buf. Returns 0 on success, -1 on error.
buf should start with the address byte (0xC8, 0xEE, etc.). */
int cel_crsf_frame_parse(cel_crsf_frame* frame, uint8_t const* buf,
size_t len);
/* Channel helpers */
int16_t cel_crsf_channel_clamp(int16_t value);
int16_t cel_crsf_channel_us_to_val(uint16_t us);
uint16_t cel_crsf_channel_val_to_us(int16_t value);
void cel_crsf_channel_default(int16_t channels[16]);
/* Telemetry parsing — see crsf_telemetry.h */
#include "celrs/crsf_telemetry.h"
/* Streaming reader — see crsf_stream.h */
#include "celrs/crsf_stream.h"
/* Parameter protocol — see crsf_param.h */
#include "celrs/crsf_param.h"
/* --- Deprecated (old frame format: [0xC8][dest][src][type][size][payload][crc]) --- */
/* Deprecated frame structure (old format). Use cel_crsf_frame instead. */
typedef struct {
uint8_t destination;
uint8_t source;
@@ -46,20 +120,11 @@ typedef struct {
uint8_t size;
uint8_t payload[255];
uint8_t crc;
} cel_crsf_frame;
} cel_crsf_frame_legacy;
/* CRC8 calculation over CRSF frame data (CCITT poly 0x07) */
uint8_t cel_crsf_crc(uint8_t const* data, size_t len);
/* Validate CRC of a CRSF frame (header already stripped, starts at dest addr) */
int cel_crsf_frame_validate(cel_crsf_frame const* frame);
/* Parse a raw buffer into a cel_crsf_frame. Returns 0 on success, -1 on error.
buf should start with 0xC8 header. */
int cel_crsf_frame_parse(cel_crsf_frame* frame, uint8_t const* buf, size_t len);
/* Build a CRSF frame into dst buffer. Returns total bytes written.
dst must have space for at least 5 + size bytes (header, addr, src, type,
size byte, payload, crc). */
size_t cel_crsf_frame_build(uint8_t* dst, uint8_t destination, uint8_t source,
uint8_t type, uint8_t const* payload, uint8_t size);
int cel_crsf_frame_validate(cel_crsf_frame_legacy const* frame);
int cel_crsf_frame_parse_legacy(cel_crsf_frame_legacy* frame, uint8_t const* buf,
size_t len);
size_t cel_crsf_frame_build_legacy(uint8_t* dst, uint8_t destination,
uint8_t source, uint8_t type,
uint8_t const* payload, uint8_t size);
+80
View File
@@ -0,0 +1,80 @@
#include "celrs/crsf_param.h"
#include <string.h>
int cel_crsf_param_ping(cel_serial_port* port, float timeout_sec) {
/* TODO: send ping frame, wait for DEVICE_INFO (0x29) response.
* Use cel_crsf_build_ping_frame() + cel_serial_write().
* Read loop with timeout using cel_serial_read().
* Use cel_crsf_stream_feed() to parse responses.
* Return 0 when DEVICE_INFO received, -1 on timeout. */
(void)port;
(void)timeout_sec;
return -1;
}
int cel_crsf_param_read(cel_serial_port* port, uint8_t index,
cel_crsf_param* out, float timeout_sec) {
/* TODO: send param read frame for index, wait for PARAM_ENTRY (0x2B).
* Use cel_crsf_build_param_read_frame() + cel_serial_write().
* Read loop with timeout, parse with cel_crsf_stream_feed().
* When PARAM_ENTRY with matching index arrives, parse payload and return. */
(void)port;
(void)index;
(void)out;
(void)timeout_sec;
return -1;
}
int cel_crsf_param_write(cel_serial_port* port, uint8_t index,
uint8_t value) {
/* TODO: send param write frame.
* Use cel_crsf_build_param_write_frame() + cel_serial_write().
* No response expected for write — fire and forget. */
(void)port;
(void)index;
(void)value;
return -1;
}
int cel_crsf_param_set_power(cel_serial_port* port, int mw,
float timeout_sec) {
/* TODO: enumerate parameters until TX Power entry is found.
* 1. Send ping, verify DEVICE_INFO response (call cel_crsf_param_ping).
* 2. For index 0..31:
* a. Send param read frame for index.
* b. Wait for PARAM_ENTRY response (timeout per param).
* c. If no response, stop (end of parameter list).
* d. If param name contains "power" (case-insensitive)
* and type is CEL_PARAM_TEXT_SELECT:
* - Search options for matching power level string
* (e.g. "10" matches "10 mW", "dynamic" matches "dynamic").
* - Send param write frame with matching option index.
* - Return 0.
* 3. If loop completes without finding power param, return -1. */
(void)port;
(void)mw;
(void)timeout_sec;
return -1;
}
int cel_crsf_param_parse(cel_crsf_param* out, uint8_t const* payload,
size_t len) {
/* TODO: parse PARAM_ENTRY payload into cel_crsf_param.
* Layout:
* [0] dest (uint8)
* [1] src (uint8)
* [2] index (uint8)
* [3] chunks_remaining (uint8)
* [4] parent (uint8)
* [5] type (uint8, bit 7 = hidden flag)
* [6..] name (null-terminated ASCII string)
* Then type-specific data after name:
* TEXT_SELECT: options (null-terminated, semicolon-separated),
* then [value][min][max][default] (1 byte each)
* UINT8/INT8: [min][max][default][value] (1 byte each)
* Minimum payload length: 6 bytes. */
(void)out;
(void)payload;
(void)len;
return -1;
}
+54
View File
@@ -0,0 +1,54 @@
#pragma once
#include <stdint.h>
#include <stddef.h>
#include "celrs/crsf.h"
#include "celrs/serial.h"
/* TX power levels (mW) */
#define CEL_POWER_10_MW 10
#define CEL_POWER_25_MW 25
#define CEL_POWER_50_MW 50
#define CEL_POWER_100_MW 100
#define CEL_POWER_250_MW 250
#define CEL_POWER_500_MW 500
#define CEL_POWER_1000_MW 1000
#define CEL_POWER_2000_MW 2000
/* Parsed parameter entry */
typedef struct {
uint8_t index;
uint8_t type; /* CEL_PARAM_* */
uint8_t hidden;
char name[64];
/* TEXT_SELECT specific */
char options[256]; /* semicolon-separated option strings */
uint8_t value;
uint8_t min_val;
uint8_t max_val;
uint8_t default_val;
} cel_crsf_param;
/* Send a device ping and wait for DEVICE_INFO response.
* Returns 0 on success, -1 on timeout/error. */
int cel_crsf_param_ping(cel_serial_port* port, float timeout_sec);
/* Read a single parameter by index.
* Returns 0 on success (out filled), -1 on timeout/error. */
int cel_crsf_param_read(cel_serial_port* port, uint8_t index,
cel_crsf_param* out, float timeout_sec);
/* Write a parameter value.
* Returns 0 on success, -1 on error. */
int cel_crsf_param_write(cel_serial_port* port, uint8_t index,
uint8_t value);
/* Set TX output power by enumerating parameters.
* mw: transmit power in mW (one of CEL_POWER_* constants).
* Returns 0 on success, -1 on error. */
int cel_crsf_param_set_power(cel_serial_port* port, int mw,
float timeout_sec);
/* Parse a PARAM_ENTRY payload into a cel_crsf_param struct.
* Returns 0 on success, -1 on bad payload. */
int cel_crsf_param_parse(cel_crsf_param* out, uint8_t const* payload,
size_t len);
+58
View File
@@ -0,0 +1,58 @@
#include "celrs/crsf_stream.h"
#include <stdlib.h>
#include <string.h>
/* Valid CRSF address bytes (frame sync bytes) */
static uint8_t const s_valid_addrs[] = {
0x00, 0xC8, 0xC4, 0xEC, 0xEE, 0xEA, 0xEF
};
static int is_valid_addr(uint8_t addr) {
for (size_t i = 0; i < sizeof(s_valid_addrs); i++) {
if (s_valid_addrs[i] == addr) return 1;
}
return 0;
}
struct cel_crsf_stream {
uint8_t buf[260]; /* internal buffer (max frame = 2 + 255 + 1 = 258) */
size_t buf_len;
};
cel_crsf_stream* cel_crsf_stream_create(void) {
/* TODO: allocate and zero-initialize the stream struct. */
return NULL;
}
void cel_crsf_stream_destroy(cel_crsf_stream* stream) {
/* TODO: free the stream struct. */
(void)stream;
}
int cel_crsf_stream_feed(cel_crsf_stream* stream, uint8_t const* data,
size_t len, cel_crsf_frame* out,
size_t out_capacity) {
/* TODO: append data to internal buffer, scan for complete frames.
* Algorithm:
* 1. Copy incoming bytes into internal buffer.
* 2. While buffer has >= 4 bytes:
* a. If buf[0] is not a valid address byte, pop(0) and continue.
* b. Read length = buf[1].
* c. Total frame = 2 + length.
* d. If buffer < total, break (need more data).
* e. Parse frame from buf[0..total-1].
* f. On success (CRC valid), copy into out[] and advance buffer.
* g. On failure (CRC invalid), discard frame and continue.
* 3. Return number of valid frames parsed, or -1 on error. */
(void)stream;
(void)data;
(void)len;
(void)out;
(void)out_capacity;
return 0;
}
void cel_crsf_stream_reset(cel_crsf_stream* stream) {
/* TODO: zero buf_len to discard any partial frame. */
(void)stream;
}
+24
View File
@@ -0,0 +1,24 @@
#pragma once
#include <stdint.h>
#include <stddef.h>
#include "celrs/crsf.h"
/* Incremental CRSF frame parser for streaming byte data.
* Accepts raw bytes and extracts complete frames as they arrive. */
typedef struct cel_crsf_stream cel_crsf_stream;
/* Create a new stream reader. Returns NULL on allocation failure. */
cel_crsf_stream* cel_crsf_stream_create(void);
/* Free the stream reader. */
void cel_crsf_stream_destroy(cel_crsf_stream* stream);
/* Feed raw bytes into the stream. Returns the number of complete frames
* parsed into out[]. out must have space for at least out_capacity frames.
* Returns -1 on error. Frames that fail CRC validation are discarded. */
int cel_crsf_stream_feed(cel_crsf_stream* stream, uint8_t const* data,
size_t len, cel_crsf_frame* out,
size_t out_capacity);
/* Reset the internal buffer (discard any partial frame). */
void cel_crsf_stream_reset(cel_crsf_stream* stream);
+164
View File
@@ -0,0 +1,164 @@
#include "celrs/crsf_telemetry.h"
#include <string.h>
int cel_crsf_telemetry_parse(cel_crsf_frame const* frame,
cel_telemetry* out) {
if (frame == NULL || out == NULL) return -1;
uint8_t const* p = frame->payload;
size_t len = frame->payload_len;
switch (frame->type) {
case CEL_CRSF_TYPE_GPS:
/* TODO: parse GPS payload (15 bytes minimum).
* Layout:
* [0..3] latitude (int32 big-endian, divide by 1e7)
* [4..7] longitude (int32 big-endian, divide by 1e7)
* [8..9] groundspeed (uint16 big-endian, divide by 10.0, km/h)
* [10..11] heading (uint16 big-endian, divide by 100.0, deg)
* [12..13] altitude (uint16 big-endian, subtract 1000, m)
* [14] satellites (uint8) */
if (len < 15) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_GPS;
break;
case CEL_CRSF_TYPE_VARIO:
/* TODO: parse vario payload (2 bytes).
* Layout: [0..1] vertical_speed (int16 big-endian, cm/s) */
if (len < 2) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_VARIO;
break;
case CEL_CRSF_TYPE_BATTERY:
/* TODO: parse battery payload (8 bytes).
* Layout:
* [0..1] voltage (uint16 big-endian mV, divide by 10.0)
* [2..3] current (uint16 big-endian mA, divide by 10.0)
* [4..6] capacity (uint24 big-endian, mAh)
* [7] remaining (uint8, percent) */
if (len < 8) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_BATTERY;
break;
case CEL_CRSF_TYPE_BARO_ALT:
/* TODO: parse baro payload (2 or 4 bytes).
* Layout:
* [0..1] altitude (uint16 big-endian).
* If MSB set: altitude = raw & 0x7FFF (meters)
* Else: altitude = (raw - 10000) / 10.0 (meters)
* [2..3] vertical_speed (int16 big-endian, cm/s) — optional */
if (len < 2) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_BARO;
break;
case CEL_CRSF_TYPE_AIRSPEED:
/* TODO: parse airspeed payload (2 bytes).
* Layout: [0..1] speed (uint16 big-endian, divide by 10.0, km/h) */
if (len < 2) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_AIRSPEED;
break;
case CEL_CRSF_TYPE_HEARTBEAT:
/* TODO: parse heartbeat payload (2 bytes).
* Layout: [0..1] origin_addr (uint16 big-endian) */
if (len < 2) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_HEARTBEAT;
break;
case CEL_CRSF_TYPE_RPM:
/* TODO: parse RPM payload (variable length).
* Layout:
* [0] source_id (uint8)
* [1..] rpm values (24-bit signed big-endian, 3 bytes each)
* Up to 8 RPM values. */
if (len < 4) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_RPM;
break;
case CEL_CRSF_TYPE_TEMP:
/* TODO: parse temperature payload (variable length).
* Layout:
* [0] source_id (uint8)
* [1..] temp values (int16 big-endian, divide by 10.0, deg C)
* Up to 8 temperature values. */
if (len < 3) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_TEMP;
break;
case CEL_CRSF_TYPE_VOLTAGES:
/* TODO: parse voltage payload (variable length).
* Layout:
* [0] source_id (uint8)
* [1..] cell voltages (uint16 big-endian mV, divide by 1000.0)
* Up to 8 cell values. */
if (len < 3) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_VOLTAGES;
break;
case CEL_CRSF_TYPE_ESC_SENSOR:
/* TODO: parse ESC sensor payload (12 bytes).
* Layout:
* [0..1] voltage (uint16 big-endian, divide by 100.0, V)
* [2..3] current (uint16 big-endian, divide by 100.0, A)
* [4..5] consumed (uint16 big-endian, mAh)
* [6..9] rpm (uint32 big-endian)
* [10] temp (uint8, deg C) */
if (len < 12) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_ESC;
break;
case CEL_CRSF_TYPE_LINK_STATS:
/* TODO: parse link stats payload (10 bytes).
* Layout:
* [0] uplink_rssi1 (uint8, 0-100%)
* [1] uplink_rssi2 (uint8, 0-100%)
* [2] uplink_quality (uint8, 0-100%)
* [3] uplink_snr (int8, signed dB)
* [4] active_antenna (uint8)
* [5] rf_mode (uint8)
* [6] uplink_power (uint8)
* [7] downlink_rssi (uint8, 0-100%)
* [8] downlink_qual (uint8, 0-100%)
* [9] downlink_snr (int8, signed dB) */
if (len < 10) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_LINK;
break;
case CEL_CRSF_TYPE_ATTITUDE:
/* TODO: parse attitude payload (6 bytes).
* Layout:
* [0..1] pitch (int16 big-endian, divide by 10000.0, radians)
* [2..3] roll (int16 big-endian, divide by 10000.0, radians)
* [4..5] yaw (int16 big-endian, divide by 10000.0, radians) */
if (len < 6) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_ATTITUDE;
break;
case CEL_CRSF_TYPE_FLIGHT_MODE:
/* TODO: parse flight mode payload (variable length string).
* Null-terminated ASCII string. Copy into out->data.flight_mode.name
* with truncation at 31 chars + null. */
if (len == 0) return -1;
memset(out, 0, sizeof(*out));
out->type = CEL_TELEM_FLIGHT_MODE;
break;
default:
return -1;
}
return 0;
}
+145
View File
@@ -0,0 +1,145 @@
#pragma once
#include <stdint.h>
#include "celrs/crsf.h"
/* Telemetry frame types */
typedef enum {
CEL_TELEM_GPS = 0,
CEL_TELEM_VARIO = 1,
CEL_TELEM_BATTERY = 2,
CEL_TELEM_BARO = 3,
CEL_TELEM_AIRSPEED = 4,
CEL_TELEM_HEARTBEAT = 5,
CEL_TELEM_RPM = 6,
CEL_TELEM_TEMP = 7,
CEL_TELEM_VOLTAGES = 8,
CEL_TELEM_ESC = 9,
CEL_TELEM_LINK = 10,
CEL_TELEM_ATTITUDE = 11,
CEL_TELEM_FLIGHT_MODE = 12,
CEL_TELEM_PARAM = 13,
CEL_TELEM_UNKNOWN = 14,
} cel_telem_type;
/* GPS telemetry */
typedef struct {
float latitude_deg;
float longitude_deg;
float groundspeed_kmh;
float heading_deg;
float altitude_m;
uint8_t satellites;
} cel_telem_gps;
/* Vario (vertical speed) */
typedef struct {
int16_t vertical_speed_cms;
} cel_telem_vario;
/* Battery sensor */
typedef struct {
float voltage_v;
float current_a;
uint32_t capacity_mah;
uint8_t remaining_pct;
} cel_telem_battery;
/* Barometric altitude */
typedef struct {
float altitude_m;
int16_t vertical_speed_cms;
} cel_telem_baro;
/* Airspeed */
typedef struct {
float speed_kmh;
} cel_telem_airspeed;
/* Heartbeat */
typedef struct {
uint16_t origin_addr;
} cel_telem_heartbeat;
/* RPM sensor (up to 8 values) */
typedef struct {
uint8_t source;
int32_t values[8];
uint8_t count;
} cel_telem_rpm;
/* Temperature sensor (up to 8 values, deg C) */
typedef struct {
uint8_t source;
float values[8];
uint8_t count;
} cel_telem_temp;
/* Voltage cells (up to 8 values, volts) */
typedef struct {
uint8_t source;
float values[8];
uint8_t count;
} cel_telem_voltages;
/* ESC telemetry (BLHeli/KISS passthrough) */
typedef struct {
float voltage_v;
float current_a;
uint16_t consumed_mah;
uint32_t rpm;
uint8_t temp_c;
} cel_telem_esc;
/* Link statistics */
typedef struct {
uint8_t uplink_rssi1;
uint8_t uplink_rssi2;
uint8_t uplink_quality;
int8_t uplink_snr;
uint8_t active_antenna;
uint8_t rf_mode;
uint8_t uplink_power;
uint8_t downlink_rssi;
uint8_t downlink_qual;
int8_t downlink_snr;
} cel_telem_link;
/* Attitude (pitch/roll/yaw in radians) */
typedef struct {
float pitch_rad;
float roll_rad;
float yaw_rad;
} cel_telem_attitude;
/* Flight mode string */
typedef struct {
char name[32];
} cel_telem_flight_mode;
/* Union of all telemetry data types */
typedef union {
cel_telem_gps gps;
cel_telem_vario vario;
cel_telem_battery battery;
cel_telem_baro baro;
cel_telem_airspeed airspeed;
cel_telem_heartbeat heartbeat;
cel_telem_rpm rpm;
cel_telem_temp temp;
cel_telem_voltages voltages;
cel_telem_esc esc;
cel_telem_link link;
cel_telem_attitude attitude;
cel_telem_flight_mode flight_mode;
} cel_telem_data;
/* Parsed telemetry frame */
typedef struct {
cel_telem_type type;
cel_telem_data data;
} cel_telemetry;
/* Parse a CRSF frame's payload into a telemetry struct.
Returns 0 on success, -1 on unsupported type or bad payload length. */
int cel_crsf_telemetry_parse(cel_crsf_frame const* frame,
cel_telemetry* out);
+29
View File
@@ -68,3 +68,32 @@ void cel_serial_free_ports(char** ports, int count) {
}
free(ports);
}
int cel_serial_find_elrs_port(char* out, size_t out_size) {
/* TODO: enumerate serial ports via cel_serial_list_ports().
* Match port description against keywords (case-insensitive):
* "silicon labs", "cp210", "elrs", "expresslrs", "bayck",
* "ch340", "ch343", "ftdi", "uart"
* Return first match. Copy device path into out.
* Return 0 on success, -1 if no match found. */
(void)out;
(void)out_size;
return -1;
}
cel_serial_port* cel_serial_open_probe(char const* path,
int const bauds[], int count,
int* out_baud) {
/* TODO: try opening the port at each baud rate in order.
* Default probe order: 921600, 400000, 420000.
* Set DTR=0, RTS=0 before opening to avoid module reset.
* On first successful open, store baud in *out_baud and return port.
* If all fail, return NULL.
* NOTE: current cel_serial_open() doesn't support DTR/RTS control.
* This needs a platform-level extension (see serial_internal.h). */
(void)path;
(void)bauds;
(void)count;
(void)out_baud;
return NULL;
}
+14
View File
@@ -32,3 +32,17 @@ int cel_serial_list_ports(char*** out_ports, int max_ports);
/* Free the port list returned by cel_serial_list_ports */
void cel_serial_free_ports(char** ports, int count);
/* Find the first serial port matching known ELRS/CP210x keywords.
* Writes the device path into out (up to out_size bytes including null).
* Returns 0 on success, -1 if no matching port found. */
int cel_serial_find_elrs_port(char* out, size_t out_size);
/* Open a serial port by probing multiple baud rates.
* bauds is an array of baud rates to try (in order), count is the array length.
* DTR/RTS are held low to avoid resetting the TX module on connect.
* Returns the opened port on success, NULL if all baud rates fail.
* The actual baud rate used is stored in *out_baud (may be NULL). */
cel_serial_port* cel_serial_open_probe(char const* path,
int const bauds[], int count,
int* out_baud);
+42 -38
View File
@@ -5,7 +5,7 @@
void setUp(void) {}
void tearDown(void) {}
/* CRC tests */
/* CRC tests — CRC8/DVB-S2 (poly 0xD5) */
void test_crc_empty(void) {
uint8_t data[1] = {0};
TEST_ASSERT_EQUAL_UINT8(0x00, cel_crsf_crc(data, 0));
@@ -18,45 +18,47 @@ void test_crc_single_byte(void) {
}
void test_crc_known_value(void) {
/* CRSF heartbeat frame data (dest+src+type+size+payload):
* {0x10, 0x80, 0x03, 0x02, 0x80, 0x01}
* Known CRC for this sequence */
/* Verify CRC is deterministic */
uint8_t data[6] = {0x10, 0x80, 0x03, 0x02, 0x80, 0x01};
uint8_t crc = cel_crsf_crc(data, 6);
TEST_ASSERT_TRUE(crc != 0);
/* Verify idempotency */
uint8_t crc2 = cel_crsf_crc(data, 6);
TEST_ASSERT_EQUAL_UINT8(crc, crc2);
}
/* Frame parse tests */
void test_parse_invalid_header(void) {
cel_crsf_frame frame;
/* TODO: rewrite parse/build tests for new ELRS frame format.
* New format: [addr][length][type][payload...][crc]
* Old tests below use legacy functions for backward compat. */
/* Frame parse tests (legacy format) */
void test_parse_legacy_invalid_header(void) {
cel_crsf_frame_legacy frame;
uint8_t buf[8] = {0x00, 0x10, 0x80, 0x03, 0x02, 0x80, 0x01, 0x00};
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse(&frame, buf, 8));
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse_legacy(&frame, buf, 8));
}
void test_parse_too_short(void) {
cel_crsf_frame frame;
void test_parse_legacy_too_short(void) {
cel_crsf_frame_legacy frame;
uint8_t buf[2] = {0xC8, 0x10};
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse(&frame, buf, 2));
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse_legacy(&frame, buf, 2));
}
void test_parse_null_frame(void) {
void test_parse_legacy_null_frame(void) {
uint8_t buf[8] = {0xC8, 0x10, 0x80, 0x03, 0x02, 0x80, 0x01, 0x00};
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse(NULL, buf, 8));
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse_legacy(NULL, buf, 8));
}
void test_parse_null_buf(void) {
cel_crsf_frame frame;
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse(&frame, NULL, 8));
void test_parse_legacy_null_buf(void) {
cel_crsf_frame_legacy frame;
TEST_ASSERT_EQUAL_INT(-1, cel_crsf_frame_parse_legacy(&frame, NULL, 8));
}
/* Frame build tests */
void test_build_heartbeat(void) {
/* Frame build tests (legacy format) */
void test_build_legacy_heartbeat(void) {
uint8_t dst[256];
uint8_t payload[2] = {0x80, 0x01};
size_t len = cel_crsf_frame_build(dst, 0x00, 0x80, 0x03, payload, 2);
size_t len = cel_crsf_frame_build_legacy(dst, 0x00, 0x80, 0x03,
payload, 2);
TEST_ASSERT_GREATER_THAN(0, len);
TEST_ASSERT_EQUAL_UINT8(CEL_CRSF_FRAME_HEADER, dst[0]);
@@ -68,14 +70,15 @@ void test_build_heartbeat(void) {
TEST_ASSERT_EQUAL_UINT8(0x01, dst[6]); /* payload[1] */
}
void test_build_roundtrip(void) {
void test_build_legacy_roundtrip(void) {
uint8_t dst[256];
uint8_t payload[4] = {0xAA, 0xBB, 0xCC, 0xDD};
size_t len = cel_crsf_frame_build(dst, 0x10, 0x80, 0x01, payload, 4);
size_t len = cel_crsf_frame_build_legacy(dst, 0x10, 0x80, 0x01,
payload, 4);
/* Parse the built frame back */
cel_crsf_frame frame;
TEST_ASSERT_EQUAL_INT(0, cel_crsf_frame_parse(&frame, dst, len));
cel_crsf_frame_legacy frame;
TEST_ASSERT_EQUAL_INT(0, cel_crsf_frame_parse_legacy(&frame, dst, len));
TEST_ASSERT_EQUAL_UINT8(0x10, frame.destination);
TEST_ASSERT_EQUAL_UINT8(0x80, frame.source);
TEST_ASSERT_EQUAL_UINT8(0x01, frame.type);
@@ -84,18 +87,19 @@ void test_build_roundtrip(void) {
TEST_ASSERT_EQUAL_UINT8(0xDD, frame.payload[3]);
}
void test_build_null_dst(void) {
void test_build_legacy_null_dst(void) {
uint8_t payload[2] = {0x01, 0x02};
TEST_ASSERT_EQUAL_UINT(0, cel_crsf_frame_build(NULL, 0x00, 0x80, 0x03, payload, 2));
TEST_ASSERT_EQUAL_UINT(0, cel_crsf_frame_build_legacy(NULL, 0x00, 0x80,
0x03, payload, 2));
}
void test_build_null_payload(void) {
void test_build_legacy_null_payload(void) {
uint8_t dst[256];
size_t len = cel_crsf_frame_build(dst, 0x10, 0x80, 0x03, NULL, 0);
size_t len = cel_crsf_frame_build_legacy(dst, 0x10, 0x80, 0x03, NULL, 0);
TEST_ASSERT_GREATER_THAN(0, len);
/* Should still have valid CRC for empty payload */
cel_crsf_frame frame;
TEST_ASSERT_EQUAL_INT(0, cel_crsf_frame_parse(&frame, dst, len));
cel_crsf_frame_legacy frame;
TEST_ASSERT_EQUAL_INT(0, cel_crsf_frame_parse_legacy(&frame, dst, len));
}
int main(void) {
@@ -103,13 +107,13 @@ int main(void) {
RUN_TEST(test_crc_empty);
RUN_TEST(test_crc_single_byte);
RUN_TEST(test_crc_known_value);
RUN_TEST(test_parse_invalid_header);
RUN_TEST(test_parse_too_short);
RUN_TEST(test_parse_null_frame);
RUN_TEST(test_parse_null_buf);
RUN_TEST(test_build_heartbeat);
RUN_TEST(test_build_roundtrip);
RUN_TEST(test_build_null_dst);
RUN_TEST(test_build_null_payload);
RUN_TEST(test_parse_legacy_invalid_header);
RUN_TEST(test_parse_legacy_too_short);
RUN_TEST(test_parse_legacy_null_frame);
RUN_TEST(test_parse_legacy_null_buf);
RUN_TEST(test_build_legacy_heartbeat);
RUN_TEST(test_build_legacy_roundtrip);
RUN_TEST(test_build_legacy_null_dst);
RUN_TEST(test_build_legacy_null_payload);
return UNITY_END();
}
+2 -1
View File
@@ -1,4 +1,5 @@
add_executable(telemetry telemetry.c)
target_include_directories(telemetry PRIVATE "${CMAKE_SOURCE_DIR}")
target_compile_features(telemetry PRIVATE c_std_23)
target_link_libraries(telemetry PRIVATE celrs_crsf celrs_serial celrs_serial_platform celrs_logger celrs_log_write)
target_link_libraries(telemetry PRIVATE celrs_crsf celrs_serial
celrs_serial_platform celrs_logger celrs_log_write)
+10 -6
View File
@@ -106,12 +106,16 @@ int main(int argc, char const* argv[]) {
snprintf(msg, sizeof(msg), "Connected to %s (%d baud)", port_path, baud_rate);
cel_log_info(msg);
/* Send heartbeat to establish CRSF link */
/* TODO: update for new ELRS frame format.
* New format uses cel_crsf_build_rc_frame() and cel_crsf_stream_feed(). */
/* Send heartbeat to establish CRSF link (legacy format) */
uint8_t hb_payload[2] = {CEL_CRSF_ADDRESS_TBS_GROUND_STATION, 0x01};
uint8_t hb_frame[256];
size_t hb_len = cel_crsf_frame_build(hb_frame, CEL_CRSF_ADDRESS_FC_BROADCAST,
size_t hb_len = cel_crsf_frame_build_legacy(hb_frame,
CEL_CRSF_ADDRESS_FC_BROADCAST,
CEL_CRSF_ADDRESS_TBS_GROUND_STATION,
CEL_CRSF_FRAMETYPE_HEARTBEAT, hb_payload, 2);
0x03, hb_payload, 2);
cel_serial_write(port, hb_frame, hb_len);
printf("RX\tLINK\tSNR\tTXP\tRSSI_RC\n");
@@ -127,13 +131,13 @@ int main(int argc, char const* argv[]) {
continue;
}
cel_crsf_frame frame;
if (cel_crsf_frame_parse(&frame, buf, n) != 0) {
cel_crsf_frame_legacy frame;
if (cel_crsf_frame_parse_legacy(&frame, buf, n) != 0) {
errors++;
continue;
}
if (frame.type != CEL_CRSF_FRAMETYPE_PACKET_LINK_TELEMETRY) {
if (frame.type != 0x02) {
continue; /* skip non-telemetry frames */
}