Skip to content

Commit acefeca

Browse files
Merge pull request iNavFlight#11025 from gismo2004/crsf_telem
[crsf] add temperature, RPM and AirSpeed telemetry
2 parents 6aedd1a + 2dc2864 commit acefeca

File tree

2 files changed

+135
-2
lines changed

2 files changed

+135
-2
lines changed

src/main/rx/crsf.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@ enum {
4646
CRSF_FRAME_VARIO_SENSOR_PAYLOAD_SIZE = 2,
4747
CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8,
4848
CRSF_FRAME_BAROMETER_ALTITUDE_PAYLOAD_SIZE = 2,
49+
CRSF_FRAME_AIRSPEED_PAYLOAD_SIZE = 2,
4950
CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10,
5051
CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE = 22, // 11 bits per channel * 16 channels = 22 bytes.
5152
CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6,
@@ -88,6 +89,9 @@ typedef enum {
8889
CRSF_FRAMETYPE_VARIO_SENSOR = 0x07,
8990
CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
9091
CRSF_FRAMETYPE_BAROMETER_ALTITUDE = 0x09,
92+
CRSF_FRAMETYPE_AIRSPEED_SENSOR = 0x0A,
93+
CRSF_FRAMETYPE_RPM = 0x0C,
94+
CRSF_FRAMETYPE_TEMP = 0x0D,
9195
CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
9296
CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
9397
CRSF_FRAMETYPE_ATTITUDE = 0x1E,

src/main/telemetry/crsf.c

Lines changed: 131 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include "fc/runtime_config.h"
4747

4848
#include "flight/imu.h"
49+
#include "flight/mixer.h"
4950

5051
#include "io/gps.h"
5152
#include "io/serial.h"
@@ -56,7 +57,10 @@
5657
#include "rx/rx.h"
5758

5859
#include "sensors/battery.h"
60+
#include "sensors/esc_sensor.h"
61+
#include "sensors/pitotmeter.h"
5962
#include "sensors/sensors.h"
63+
#include "sensors/temperature.h"
6064

6165
#include "telemetry/crsf.h"
6266
#include "telemetry/telemetry.h"
@@ -162,6 +166,16 @@ static void crsfSerialize16(sbuf_t *dst, uint16_t v)
162166
crsfSerialize8(dst, (uint8_t)v);
163167
}
164168

169+
#ifdef USE_ESC_SENSOR
170+
static void crsfSerialize24(sbuf_t *dst, uint32_t v)
171+
{
172+
// Use BigEndian format
173+
crsfSerialize8(dst, (v >> 16));
174+
crsfSerialize8(dst, (v >> 8));
175+
crsfSerialize8(dst, (uint8_t)v);
176+
}
177+
#endif
178+
165179
static void crsfSerialize32(sbuf_t *dst, uint32_t v)
166180
{
167181
// Use BigEndian format
@@ -296,6 +310,86 @@ static void crsfBarometerAltitude(sbuf_t *dst)
296310
crsfSerialize16(dst, altitude_packed);
297311
}
298312

313+
#ifdef USE_PITOT
314+
/*
315+
0x0A Airspeed sensor
316+
Payload:
317+
int16 Air speed ( dm/s )
318+
*/
319+
static void crsfFrameAirSpeedSensor(sbuf_t *dst)
320+
{
321+
// use sbufWrite since CRC does not include frame length
322+
sbufWriteU8(dst, CRSF_FRAME_AIRSPEED_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC);
323+
crsfSerialize8(dst, CRSF_FRAMETYPE_AIRSPEED_SENSOR);
324+
crsfSerialize16(dst, (uint16_t)(getAirspeedEstimate() * 36 / 100));
325+
}
326+
#endif
327+
328+
#ifdef USE_ESC_SENSOR
329+
/*
330+
0x0C RPM
331+
Payload:
332+
uint8_t rpm_source_id; // Identifies the source of the RPM data (e.g., 0 = Motor 1, 1 = Motor 2, etc.)
333+
int24_t rpm_value[]; // 1 - 19 RPM values with negative ones representing the motor spinning in reverse
334+
*/
335+
static void crsfRpm(sbuf_t *dst)
336+
{
337+
uint8_t motorCount = getMotorCount();
338+
339+
if (STATE(ESC_SENSOR_ENABLED) && motorCount > 0) {
340+
sbufWriteU8(dst, 1 + (motorCount * 3) + CRSF_FRAME_LENGTH_TYPE_CRC);
341+
crsfSerialize8(dst, CRSF_FRAMETYPE_RPM);
342+
// 0 = FC including all ESCs
343+
crsfSerialize8(dst, 0);
344+
345+
for (uint8_t i = 0; i < motorCount; i++) {
346+
const escSensorData_t *escState = getEscTelemetry(i);
347+
crsfSerialize24(dst, (escState) ? escState->rpm : 0);
348+
}
349+
}
350+
}
351+
#endif
352+
353+
/*
354+
0x0D TEMP
355+
Payload:
356+
uint8_t temp_source_id; // Identifies the source of the temperature data (e.g., 0 = FC including all ESCs, 1 = Ambient, etc.)
357+
int16_t temperature[]; // up to 20 temperature values in deci-degree (tenths of a degree) Celsius (e.g., 250 = 25.0°C, -50 = -5.0°C)
358+
*/
359+
static void crsfTemperature(sbuf_t *dst)
360+
{
361+
362+
uint8_t tempCount = 0;
363+
int16_t temperatures[20];
364+
365+
#ifdef USE_ESC_SENSOR
366+
uint8_t motorCount = getMotorCount();
367+
if (STATE(ESC_SENSOR_ENABLED) && motorCount > 0) {
368+
for (uint8_t i = 0; i < motorCount; i++) {
369+
const escSensorData_t *escState = getEscTelemetry(i);
370+
temperatures[tempCount++] = (escState) ? escState->temperature * 10 : TEMPERATURE_INVALID_VALUE;
371+
}
372+
}
373+
#endif
374+
375+
#ifdef USE_TEMPERATURE_SENSOR
376+
for (uint8_t i = 0; i < MAX_TEMP_SENSORS; i++) {
377+
int16_t value;
378+
if (getSensorTemperature(i, &value))
379+
temperatures[tempCount++] = value;
380+
}
381+
#endif
382+
383+
if (tempCount > 0) {
384+
sbufWriteU8(dst, 1 + (tempCount * 2) + CRSF_FRAME_LENGTH_TYPE_CRC);
385+
crsfSerialize8(dst, CRSF_FRAMETYPE_TEMP);
386+
// 0 = FC including all ESCs
387+
crsfSerialize8(dst, 0);
388+
for (uint8_t i = 0; i < tempCount; i++)
389+
crsfSerialize16(dst, temperatures[i]);
390+
}
391+
}
392+
299393
typedef enum {
300394
CRSF_ACTIVE_ANTENNA1 = 0,
301395
CRSF_ACTIVE_ANTENNA2 = 1
@@ -465,11 +559,14 @@ typedef enum {
465559
CRSF_FRAME_GPS_INDEX,
466560
CRSF_FRAME_VARIO_SENSOR_INDEX,
467561
CRSF_FRAME_BAROMETER_ALTITUDE_INDEX,
562+
CRSF_FRAME_TEMP_INDEX,
563+
CRSF_FRAME_RPM_INDEX,
564+
CRSF_FRAME_AIRSPEED_INDEX,
468565
CRSF_SCHEDULE_COUNT_MAX
469566
} crsfFrameTypeIndex_e;
470567

471568
static uint8_t crsfScheduleCount;
472-
static uint8_t crsfSchedule[CRSF_SCHEDULE_COUNT_MAX];
569+
static uint16_t crsfSchedule[CRSF_SCHEDULE_COUNT_MAX];
473570

474571
#if defined(USE_MSP_OVER_TELEMETRY)
475572

@@ -506,7 +603,7 @@ static void processCrsf(void)
506603
}
507604

508605
static uint8_t crsfScheduleIndex = 0;
509-
const uint8_t currentSchedule = crsfSchedule[crsfScheduleIndex];
606+
const uint16_t currentSchedule = crsfSchedule[crsfScheduleIndex];
510607

511608
sbuf_t crsfPayloadBuf;
512609
sbuf_t *dst = &crsfPayloadBuf;
@@ -526,6 +623,20 @@ static void processCrsf(void)
526623
crsfFrameFlightMode(dst);
527624
crsfFinalize(dst);
528625
}
626+
#ifdef USE_ESC_SENSOR
627+
if (currentSchedule & BV(CRSF_FRAME_RPM_INDEX)) {
628+
crsfInitializeFrame(dst);
629+
crsfRpm(dst);
630+
crsfFinalize(dst);
631+
}
632+
#endif
633+
#if defined(USE_ESC_SENSOR) || defined(USE_TEMPERATURE_SENSOR)
634+
if (currentSchedule & BV(CRSF_FRAME_TEMP_INDEX)) {
635+
crsfInitializeFrame(dst);
636+
crsfTemperature(dst);
637+
crsfFinalize(dst);
638+
}
639+
#endif
529640
#ifdef USE_GPS
530641
if (currentSchedule & BV(CRSF_FRAME_GPS_INDEX)) {
531642
crsfInitializeFrame(dst);
@@ -544,6 +655,13 @@ static void processCrsf(void)
544655
crsfBarometerAltitude(dst);
545656
crsfFinalize(dst);
546657
}
658+
#endif
659+
#ifdef USE_PITOT
660+
if (currentSchedule & BV(CRSF_FRAME_AIRSPEED_INDEX)) {
661+
crsfInitializeFrame(dst);
662+
crsfFrameAirSpeedSensor(dst);
663+
crsfFinalize(dst);
664+
}
547665
#endif
548666
crsfScheduleIndex = (crsfScheduleIndex + 1) % crsfScheduleCount;
549667
}
@@ -582,6 +700,17 @@ void initCrsfTelemetry(void)
582700
if (sensors(SENSOR_BARO)) {
583701
crsfSchedule[index++] = BV(CRSF_FRAME_BAROMETER_ALTITUDE_INDEX);
584702
}
703+
#endif
704+
#ifdef USE_ESC_SENSOR
705+
crsfSchedule[index++] = BV(CRSF_FRAME_RPM_INDEX);
706+
#endif
707+
#if defined(USE_ESC_SENSOR) || defined(USE_TEMPERATURE_SENSOR)
708+
crsfSchedule[index++] = BV(CRSF_FRAME_TEMP_INDEX);
709+
#endif
710+
#ifdef USE_PITOT
711+
if (sensors(SENSOR_PITOT)) {
712+
crsfSchedule[index++] = BV(CRSF_FRAME_AIRSPEED_INDEX);
713+
}
585714
#endif
586715
crsfScheduleCount = (uint8_t)index;
587716
}

0 commit comments

Comments
 (0)