Skip to content

Commit

Permalink
Refactor CRSF telemetry
Browse files Browse the repository at this point in the history
This commit introduces Custom CRSF Telemetry.

It is using a "custom" CRSF frame (0x88) for passing the telemetry
data to the Tx. On the Tx side, a LUA script is parsing these frames
and injecting the sensors into the native sensor framework.

The FC has over hundred telemetry sensors to choose from.
Up to 40 can be enabled at the same time. Depending on the link
bandwidth (up to 20kbit/s with ELRS), sensor update rates up to 50Hz
are achievable.

This framework is also fully extensible in the future. For adding
new sensors, changes in the firmware and the LUA script is needed.
The Receiver or the Transmitter are not involved in the process.
  • Loading branch information
pmattila committed Jul 25, 2024
1 parent 240a40e commit 7e973c2
Show file tree
Hide file tree
Showing 20 changed files with 1,908 additions and 1,085 deletions.
1 change: 1 addition & 0 deletions make/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -191,6 +191,7 @@ COMMON_SRC = \
telemetry/msp_shared.c \
telemetry/ibus.c \
telemetry/ibus_shared.c \
telemetry/sensors.c \
sensors/esc_sensor.c \
io/vtx.c \
io/vtx_rtc6705.c \
Expand Down
41 changes: 11 additions & 30 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -484,26 +484,14 @@ const char * const lookupTableSwashType[] = {
"NONE", "PASSTHROUGH", "CP120", "CP135", "CP140", "FP90L", "FP90V",
};

const char * const lookupTableCrsfFmReuse[] = {
"NONE", "GOVERNOR", "HEADSPEED", "THROTTLE", "ESC_TEMP", "MCU_TEMP", "MCU_LOAD", "SYS_LOAD", "RT_LOAD", "BEC_VOLTAGE", "BUS_VOLTAGE", "MCU_VOLTAGE", "ADJFUNC", "GOV_ADJFUNC",
};

const char * const lookupTableCrsfAttReuse[] = {
"NONE", "THROTTLE", "ESC_TEMP", "ESC_PWM", "ESC_BEC_VOLTAGE", "ESC_BEC_CURRENT", "ESC_BEC_TEMP", "ESC_STATUS", "ESC_STATUS2", "MCU_TEMP", "MCU_LOAD", "SYS_LOAD", "RT_LOAD", "BEC_VOLTAGE", "BUS_VOLTAGE", "MCU_VOLTAGE",
};

const char * const lookupTableCrsfGpsReuse[] = {
"NONE", "HEADSPEED", "THROTTLE", "ESC_TEMP", "ESC_PWM", "ESC_THROTTLE", "ESC_BEC_VOLTAGE", "ESC_BEC_CURRENT", "ESC_BEC_TEMP", "ESC_STATUS", "ESC_STATUS2", "MCU_TEMP", "MCU_LOAD", "SYS_LOAD", "RT_LOAD", "BEC_VOLTAGE", "BUS_VOLTAGE", "MCU_VOLTAGE",
};

const char * const lookupTableCrsfGpsSatsReuse[] = {
"NONE", "ESC_TEMP", "MCU_TEMP", "PROFILE", "RATE_PROFILE", "LED_PROFILE", "MODEL_ID",
};

const char * const lookupTableDtermMode[] = {
"GYRO", "ERROR",
};

const char * const lookupTableTelemMode[] = {
"NATIVE", "CUSTOM",
};

#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }

const lookupTableEntry_t lookupTables[] = {
Expand Down Expand Up @@ -613,11 +601,8 @@ const lookupTableEntry_t lookupTables[] = {

LOOKUP_TABLE_ENTRY(lookupTableRescueMode),
LOOKUP_TABLE_ENTRY(lookupTableSwashType),
LOOKUP_TABLE_ENTRY(lookupTableCrsfFmReuse),
LOOKUP_TABLE_ENTRY(lookupTableCrsfAttReuse),
LOOKUP_TABLE_ENTRY(lookupTableCrsfGpsReuse),
LOOKUP_TABLE_ENTRY(lookupTableCrsfGpsSatsReuse),
LOOKUP_TABLE_ENTRY(lookupTableDtermMode),
LOOKUP_TABLE_ENTRY(lookupTableTelemMode),
};

#undef LOOKUP_TABLE_ENTRY
Expand Down Expand Up @@ -1200,15 +1185,11 @@ const clivalue_t valueTable[] = {
// Set to $size_of_battery to get a percentage of battery used.
{ "mavlink_mah_as_heading_divisor", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 30000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, mavlink_mah_as_heading_divisor) },
#endif
{ "crsf_flight_mode_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_FM_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_flight_mode_reuse) },
{ "crsf_att_pitch_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_ATT_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_att_pitch_reuse) },
{ "crsf_att_roll_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_ATT_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_att_roll_reuse) },
{ "crsf_att_yaw_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_ATT_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_att_yaw_reuse) },

{ "crsf_gps_heading_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_GPS_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_gps_heading_reuse) },
{ "crsf_gps_ground_speed_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_GPS_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_gps_ground_speed_reuse) },
{ "crsf_gps_altitude_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_GPS_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_gps_altitude_reuse) },
{ "crsf_gps_sats_reuse", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CRSF_GPS_SATS_REUSE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_gps_sats_reuse) },
{ "crsf_telemetry_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_TELEM_MODE }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_telemetry_mode) },
{ "crsf_telemetry_link_rate", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 50000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_telemetry_link_rate) },
{ "crsf_telemetry_link_ratio", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 50000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_telemetry_link_ratio) },
{ "crsf_telemetry_sensors", VAR_UINT16 | MASTER_VALUE | MODE_ARRAY, .config.array.length = TELEM_SENSOR_SLOT_COUNT, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_telemetry_sensors)},
{ "crsf_telemetry_interval", VAR_UINT16 | MASTER_VALUE | MODE_ARRAY, .config.array.length = TELEM_SENSOR_SLOT_COUNT, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, crsf_telemetry_interval)},

#ifdef USE_TELEMETRY_ENABLE_SENSORS
{ "telemetry_enable_voltage", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = LOG2(SENSOR_VOLTAGE), PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, enableSensors)},
Expand All @@ -1235,7 +1216,7 @@ const clivalue_t valueTable[] = {
{ "telemetry_enable_adjustment", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = LOG2(SENSOR_ADJUSTMENT), PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, enableSensors)},
{ "telemetry_enable_gov_mode", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = LOG2(SENSOR_GOV_MODE), PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, enableSensors)},
#else
{ "telemetry_enable_sensors", VAR_UINT32 | MASTER_VALUE, .config.u32Max = SENSOR_ALL, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, enableSensors)},
{ "telemetry_enable_sensors", VAR_UINT32 | MASTER_VALUE, .config.u32Max = SENSOR_ALL, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, enableSensors)},
#endif
#endif // USE_TELEMETRY

Expand Down
5 changes: 1 addition & 4 deletions src/main/cli/settings.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,11 +127,8 @@ typedef enum {
#endif
TABLE_RESCUE_MODE,
TABLE_SWASH_TYPE,
TABLE_CRSF_FM_REUSE,
TABLE_CRSF_ATT_REUSE,
TABLE_CRSF_GPS_REUSE,
TABLE_CRSF_GPS_SATS_REUSE,
TABLE_DTERM_MODE,
TABLE_TELEM_MODE,

LOOKUP_TABLE_COUNT
} lookupTableIndex_e;
Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/tasks.c
Original file line number Diff line number Diff line change
Expand Up @@ -503,8 +503,8 @@ void tasksInit(void)
// Reschedule telemetry to 500hz for Jeti Exbus
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
} else if (rxRuntimeState.serialrxProvider == SERIALRX_CRSF) {
// Reschedule telemetry to 500hz, 2ms for CRSF
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
// Reschedule telemetry to 1000hz, 1ms for CRSF
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(1000));
}
}
#endif
Expand Down
14 changes: 14 additions & 0 deletions src/main/msp/msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1581,6 +1581,12 @@ static bool mspProcessOutCommand(int16_t cmdMSP, sbuf_t *dst)
sbufWriteU8(dst, telemetryConfig()->halfDuplex);
sbufWriteU32(dst, telemetryConfig()->enableSensors);
sbufWriteU8(dst, telemetryConfig()->pinSwap);
sbufWriteU8(dst, telemetryConfig()->crsf_telemetry_mode);
sbufWriteU16(dst, telemetryConfig()->crsf_telemetry_link_rate);
sbufWriteU16(dst, telemetryConfig()->crsf_telemetry_link_ratio);
for (int i = 0; i < TELEM_SENSOR_SLOT_COUNT; i++) {
sbufWriteU8(dst, telemetryConfig()->crsf_telemetry_sensors[i]);
}
break;

case MSP_SERIAL_CONFIG:
Expand Down Expand Up @@ -3089,6 +3095,14 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
if (sbufBytesRemaining(src) >= 1) {
telemetryConfigMutable()->pinSwap = sbufReadU8(src);
}
if (sbufBytesRemaining(src) >= 5 + TELEM_SENSOR_SLOT_COUNT) {
telemetryConfigMutable()->crsf_telemetry_mode = sbufReadU8(src);
telemetryConfigMutable()->crsf_telemetry_link_rate = sbufReadU16(src);
telemetryConfigMutable()->crsf_telemetry_link_ratio = sbufReadU16(src);
for (int i = 0; i < TELEM_SENSOR_SLOT_COUNT; i++) {
telemetryConfigMutable()->crsf_telemetry_sensors[i] = sbufReadU8(src);
}
}
break;

case MSP_SET_SERIAL_CONFIG:
Expand Down
22 changes: 10 additions & 12 deletions src/main/pg/telemetry.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,11 @@

#include "common/unit.h"

#include "config/config.h"

#include "pg/pg_ids.h"
#include "pg/telemetry.h"

#include "telemetry/crsf.h"


PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 5);
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 6);

PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_inverted = false,
Expand All @@ -44,9 +41,9 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.pidValuesAsTelemetry = 0,
.report_cell_voltage = false,
.flysky_sensors = {
IBUS_SENSOR_TYPE_TEMPERATURE,
IBUS_SENSOR_TYPE_RPM_FLYSKY,
IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
IBUS_SENSOR_TYPE_TEMPERATURE,
IBUS_SENSOR_TYPE_RPM_FLYSKY,
IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE
},
.enableSensors =
SENSOR_VOLTAGE |
Expand All @@ -57,10 +54,11 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
ESC_SENSOR_RPM |
ESC_SENSOR_TEMPERATURE,
.mavlink_mah_as_heading_divisor = 0,
.crsf_flight_mode_reuse = CRSF_FM_REUSE_NONE,
.crsf_att_pitch_reuse = CRSF_ATT_REUSE_NONE,
.crsf_att_roll_reuse = CRSF_ATT_REUSE_NONE,
.crsf_att_yaw_reuse = CRSF_ATT_REUSE_NONE,
.crsf_telemetry_mode = CRSF_TELEMETRY_MODE_NATIVE,
.crsf_telemetry_sensors = INIT_ZERO,
.crsf_telemetry_interval = INIT_ZERO,
.crsf_telemetry_link_rate = 250,
.crsf_telemetry_link_ratio = 8,
);

#endif
75 changes: 38 additions & 37 deletions src/main/pg/telemetry.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,43 +23,46 @@

#include "pg/pg.h"


typedef enum {
SENSOR_VOLTAGE = 1 << 0,
SENSOR_CURRENT = 1 << 1,
SENSOR_FUEL = 1 << 2,
SENSOR_MODE = 1 << 3,
SENSOR_ACC_X = 1 << 4,
SENSOR_ACC_Y = 1 << 5,
SENSOR_ACC_Z = 1 << 6,
SENSOR_PITCH = 1 << 7,
SENSOR_ROLL = 1 << 8,
SENSOR_HEADING = 1 << 9,
SENSOR_ALTITUDE = 1 << 10,
SENSOR_VARIO = 1 << 11,
SENSOR_LAT_LONG = 1 << 12,
SENSOR_GROUND_SPEED = 1 << 13,
SENSOR_DISTANCE = 1 << 14,
ESC_SENSOR_CURRENT = 1 << 15,
ESC_SENSOR_VOLTAGE = 1 << 16,
ESC_SENSOR_RPM = 1 << 17,
ESC_SENSOR_TEMPERATURE = 1 << 18,
ESC_SENSOR_ALL = ESC_SENSOR_CURRENT \
| ESC_SENSOR_VOLTAGE \
| ESC_SENSOR_RPM \
| ESC_SENSOR_TEMPERATURE,
SENSOR_TEMPERATURE = 1 << 19,
SENSOR_CAP_USED = 1 << 20,
SENSOR_ADJUSTMENT = 1 << 21,
SENSOR_GOV_MODE = 1 << 22,
SENSOR_ALL = (1 << 23) - 1,
SENSOR_VOLTAGE = BIT(0),
SENSOR_CURRENT = BIT(1),
SENSOR_FUEL = BIT(2),
SENSOR_MODE = BIT(3),
SENSOR_ACC_X = BIT(4),
SENSOR_ACC_Y = BIT(5),
SENSOR_ACC_Z = BIT(6),
SENSOR_PITCH = BIT(7),
SENSOR_ROLL = BIT(8),
SENSOR_HEADING = BIT(9),
SENSOR_ALTITUDE = BIT(10),
SENSOR_VARIO = BIT(11),
SENSOR_LAT_LONG = BIT(12),
SENSOR_GROUND_SPEED = BIT(13),
SENSOR_DISTANCE = BIT(14),
ESC_SENSOR_CURRENT = BIT(15),
ESC_SENSOR_VOLTAGE = BIT(16),
ESC_SENSOR_RPM = BIT(17),
ESC_SENSOR_TEMPERATURE = BIT(18),
SENSOR_TEMPERATURE = BIT(19),
SENSOR_CAP_USED = BIT(20),
SENSOR_ADJUSTMENT = BIT(21),
SENSOR_GOV_MODE = BIT(22),
} sensor_e;

typedef enum {
FRSKY_FORMAT_DMS = 0,
FRSKY_FORMAT_NMEA
} frskyGpsCoordFormat_e;

typedef struct {
enum {
CRSF_TELEMETRY_MODE_NATIVE = 0,
CRSF_TELEMETRY_MODE_CUSTOM,
};

#define TELEM_SENSOR_SLOT_COUNT 40

typedef struct telemetryConfig_s {
int16_t gpsNoFixLatitude;
int16_t gpsNoFixLongitude;
uint8_t telemetry_inverted;
Expand All @@ -73,15 +76,13 @@ typedef struct {
uint8_t report_cell_voltage;
uint8_t flysky_sensors[IBUS_SENSOR_COUNT];
uint16_t mavlink_mah_as_heading_divisor;
uint8_t crsf_flight_mode_reuse;
uint8_t crsf_att_pitch_reuse;
uint8_t crsf_att_roll_reuse;
uint8_t crsf_att_yaw_reuse;
uint8_t crsf_gps_heading_reuse;
uint8_t crsf_gps_ground_speed_reuse;
uint8_t crsf_gps_altitude_reuse;
uint8_t crsf_gps_sats_reuse;
uint32_t enableSensors;
uint8_t crsf_telemetry_mode;
uint16_t crsf_telemetry_sensors[TELEM_SENSOR_SLOT_COUNT];
uint16_t crsf_telemetry_interval[TELEM_SENSOR_SLOT_COUNT];
uint16_t crsf_telemetry_link_rate;
uint16_t crsf_telemetry_link_ratio;
} telemetryConfig_t;

PG_DECLARE(telemetryConfig_t, telemetryConfig);

31 changes: 8 additions & 23 deletions src/main/rx/crsf.c
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,6 @@ STATIC_UNIT_TESTED uint32_t crsfChannelData[CRSF_MAX_CHANNEL];

static serialPort_t *serialPort;
static timeUs_t crsfFrameStartAtUs = 0;
static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
static float channelScale = CRSF_RC_CHANNEL_SCALE_LEGACY;

#ifdef USE_RX_LINK_UPLINK_POWER
Expand Down Expand Up @@ -337,6 +335,7 @@ STATIC_UNIT_TESTED uint8_t crsfFrameCRC(void)
return crc;
}

#if defined(USE_CRSF_V3)
STATIC_UNIT_TESTED uint8_t crsfFrameCmdCRC(void)
{
// CRC includes type and payload
Expand All @@ -346,6 +345,7 @@ STATIC_UNIT_TESTED uint8_t crsfFrameCmdCRC(void)
}
return crc;
}
#endif

// Receive ISR callback, called back from serial port
STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
Expand Down Expand Up @@ -412,17 +412,13 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
}
#endif
#if defined(USE_CRSF_CMS_TELEMETRY)
case CRSF_FRAMETYPE_DEVICE_PING:
crsfScheduleDeviceInfoResponse();
break;
case CRSF_FRAMETYPE_DISPLAYPORT_CMD: {
uint8_t *frameStart = (uint8_t *)&crsfFrame.frame.payload + CRSF_FRAME_ORIGIN_DEST_SIZE;
crsfProcessDisplayPortCmd(frameStart);
break;
}
#endif
#if defined(USE_CRSF_LINK_STATISTICS)

case CRSF_FRAMETYPE_LINK_STATISTICS: {
// if to FC and 10 bytes + CRSF_FRAME_ORIGIN_DEST_SIZE
if ((rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) &&
Expand Down Expand Up @@ -456,6 +452,9 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
}
break;
#endif
case CRSF_FRAMETYPE_DEVICE_PING:
crsfScheduleDeviceInfoResponse();
break;
default:
break;
}
Expand Down Expand Up @@ -598,27 +597,13 @@ STATIC_UNIT_TESTED float crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, u
}
}

void crsfRxWriteTelemetryData(const void *data, int len)
{
len = MIN(len, (int)sizeof(telemetryBuf));
memcpy(telemetryBuf, data, len);
telemetryBufLen = len;
}

void crsfRxSendTelemetryData(void)
void crsfRxTransmitTelemetryData(const void *data, int len)
{
// if there is telemetry data to write
if (telemetryBufLen > 0) {
serialWriteBuf(serialPort, telemetryBuf, telemetryBufLen);
telemetryBufLen = 0; // reset telemetry buffer
if (len > 0 && len <= CRSF_FRAME_SIZE_MAX) {
serialWriteBuf(serialPort, data, len);
}
}

bool crsfRxIsTelemetryBufEmpty(void)
{
return telemetryBufLen == 0;
}

bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
for (int ii = 0; ii < CRSF_MAX_CHANNEL; ++ii) {
Expand Down
4 changes: 1 addition & 3 deletions src/main/rx/crsf.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,7 @@ typedef union crsfFrame_u {
crsfFrameDef_t frame;
} crsfFrame_t;

void crsfRxWriteTelemetryData(const void *data, int len);
void crsfRxSendTelemetryData(void);
bool crsfRxIsTelemetryBufEmpty(void); // check this function before using crsfRxWriteTelemetryData()
void crsfRxTransmitTelemetryData(const void *data, int len);

struct rxConfig_s;
struct rxRuntimeState_s;
Expand Down
Loading

0 comments on commit 7e973c2

Please sign in to comment.