PX4 Firmware
PX4 Autopilot Software http://px4.io
crsf.cpp File Reference
#include <drivers/drv_hrt.h>
#include <termios.h>
#include <string.h>
#include <unistd.h>
#include "crsf.h"
#include "common_rc.h"
Include dependency graph for crsf.cpp:

Go to the source code of this file.

Classes

struct  crsf_payload_RC_channels_packed_t
 

Macros

#define CRSF_DEBUG(...)
 
#define CRSF_VERBOSE(...)
 
#define MIN(a, b)   (((a)<(b))?(a):(b))
 
#define MAX(a, b)   (((a)>(b))?(a):(b))
 
#define CRSF_BAUDRATE   420000
 
#define CRSF_SYNC_BYTE   0xC8
 

Enumerations

enum  crsf_frame_type_t : uint8_t {
  crsf_frame_type_t::gps = 0x02, crsf_frame_type_t::battery_sensor = 0x08, crsf_frame_type_t::link_statistics = 0x14, crsf_frame_type_t::rc_channels_packed = 0x16,
  crsf_frame_type_t::attitude = 0x1E, crsf_frame_type_t::flight_mode = 0x21, crsf_frame_type_t::device_ping = 0x28, crsf_frame_type_t::device_info = 0x29,
  crsf_frame_type_t::parameter_settings_entry = 0x2B, crsf_frame_type_t::parameter_read = 0x2C, crsf_frame_type_t::parameter_write = 0x2D, crsf_frame_type_t::command = 0x32
}
 
enum  crsf_payload_size_t : uint8_t {
  crsf_payload_size_t::gps = 15, crsf_payload_size_t::battery_sensor = 8, crsf_payload_size_t::link_statistics = 10, crsf_payload_size_t::rc_channels = 22,
  crsf_payload_size_t::attitude = 6
}
 
enum  crsf_address_t : uint8_t {
  crsf_address_t::broadcast = 0x00, crsf_address_t::usb = 0x10, crsf_address_t::tbs_core_pnp_pro = 0x80, crsf_address_t::reserved1 = 0x8A,
  crsf_address_t::current_sensor = 0xC0, crsf_address_t::gps = 0xC2, crsf_address_t::tbs_blackbox = 0xC4, crsf_address_t::flight_controller = 0xC8,
  crsf_address_t::reserved2 = 0xCA, crsf_address_t::race_tag = 0xCC, crsf_address_t::radio_transmitter = 0xEA, crsf_address_t::crsf_receiver = 0xEC,
  crsf_address_t::crsf_transmitter = 0xEE
}
 
enum  crsf_parser_state_t : uint8_t { crsf_parser_state_t::unsynced = 0, crsf_parser_state_t::synced }
 

Functions

static bool crsf_parse_buffer (uint16_t *values, uint16_t *num_values, uint16_t max_channels)
 parse the current crsf_frame buffer More...
 
static uint8_t crc8_dvb_s2 (uint8_t crc, uint8_t a)
 
static uint8_t crc8_dvb_s2_buf (uint8_t *buf, int len)
 
uint8_t crsf_frame_CRC (const crsf_frame_t &frame)
 
int crsf_config (int uart_fd)
 Configure an UART port to be used for CRSF. More...
 
static uint16_t convert_channel_value (unsigned chan_value)
 Convert from RC to PWM value. More...
 
bool crsf_parse (const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values, uint16_t *num_values, uint16_t max_channels)
 Parse the CRSF protocol and extract RC channel data. More...
 
static void write_uint8_t (uint8_t *buf, int &offset, uint8_t value)
 write an uint8_t value to a buffer at a given offset and increment the offset More...
 
static void write_uint16_t (uint8_t *buf, int &offset, uint16_t value)
 write an uint16_t value to a buffer at a given offset and increment the offset More...
 
static void write_uint24_t (uint8_t *buf, int &offset, int value)
 write an uint24_t value to a buffer at a given offset and increment the offset More...
 
static void write_int32_t (uint8_t *buf, int &offset, int32_t value)
 write an int32_t value to a buffer at a given offset and increment the offset More...
 
static void write_frame_header (uint8_t *buf, int &offset, crsf_frame_type_t type, uint8_t payload_size)
 
static void write_frame_crc (uint8_t *buf, int &offset, int buf_size)
 
bool crsf_send_telemetry_battery (int uart_fd, uint16_t voltage, uint16_t current, int fuel, uint8_t remaining)
 Send telemetry battery information. More...
 
bool crsf_send_telemetry_gps (int uart_fd, int32_t latitude, int32_t longitude, uint16_t groundspeed, uint16_t gps_heading, uint16_t altitude, uint8_t num_satellites)
 Send telemetry GPS information. More...
 
bool crsf_send_telemetry_attitude (int uart_fd, int16_t pitch, int16_t roll, int16_t yaw)
 Send telemetry Attitude information. More...
 
bool crsf_send_telemetry_flight_mode (int uart_fd, const char *flight_mode)
 Send telemetry Flight Mode information. More...
 

Variables

static crsf_frame_tcrsf_frame = rc_decode_buf.crsf_frame
 
static unsigned current_frame_position = 0
 
static crsf_parser_state_t parser_state = crsf_parser_state_t::unsynced
 

Macro Definition Documentation

◆ CRSF_BAUDRATE

#define CRSF_BAUDRATE   420000

Definition at line 58 of file crsf.cpp.

Referenced by crsf_config().

◆ CRSF_DEBUG

#define CRSF_DEBUG (   ...)

Definition at line 37 of file crsf.cpp.

Referenced by crsf_parse(), and crsf_parse_buffer().

◆ CRSF_SYNC_BYTE

#define CRSF_SYNC_BYTE   0xC8

Definition at line 60 of file crsf.cpp.

Referenced by write_frame_header().

◆ CRSF_VERBOSE

#define CRSF_VERBOSE (   ...)

Definition at line 43 of file crsf.cpp.

Referenced by crsf_parse_buffer().

◆ MAX

#define MAX (   a,
 
)    (((a)>(b))?(a):(b))

Definition at line 55 of file crsf.cpp.

◆ MIN

#define MIN (   a,
 
)    (((a)<(b))?(a):(b))

Definition at line 54 of file crsf.cpp.

Referenced by crsf_parse(), and crsf_parse_buffer().

Enumeration Type Documentation

◆ crsf_address_t

enum crsf_address_t : uint8_t
strong
Enumerator
broadcast 
usb 
tbs_core_pnp_pro 
reserved1 
current_sensor 
gps 
tbs_blackbox 
flight_controller 
reserved2 
race_tag 
radio_transmitter 
crsf_receiver 
crsf_transmitter 

Definition at line 88 of file crsf.cpp.

◆ crsf_frame_type_t

enum crsf_frame_type_t : uint8_t
strong
Enumerator
gps 
battery_sensor 
link_statistics 
rc_channels_packed 
attitude 
flight_mode 
device_ping 
device_info 
parameter_settings_entry 
parameter_read 
parameter_write 
command 

Definition at line 62 of file crsf.cpp.

◆ crsf_parser_state_t

enum crsf_parser_state_t : uint8_t
strong
Enumerator
unsynced 
synced 

Definition at line 127 of file crsf.cpp.

◆ crsf_payload_size_t

enum crsf_payload_size_t : uint8_t
strong
Enumerator
gps 
battery_sensor 
link_statistics 
rc_channels 

11 bits per channel * 16 channels = 22 bytes.

attitude 

Definition at line 79 of file crsf.cpp.

Function Documentation

◆ convert_channel_value()

static uint16_t convert_channel_value ( unsigned  chan_value)
static

Convert from RC to PWM value.

Parameters
chan_valuechannel value in [172, 1811]
Returns
PWM channel value in [1000, 2000]

Definition at line 244 of file crsf.cpp.

References f().

Referenced by crsf_config(), and crsf_parse_buffer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crc8_dvb_s2()

static uint8_t crc8_dvb_s2 ( uint8_t  crc,
uint8_t  a 
)
static

Definition at line 205 of file crsf.cpp.

Referenced by crc8_dvb_s2_buf(), and crsf_frame_CRC().

Here is the caller graph for this function:

◆ crc8_dvb_s2_buf()

static uint8_t crc8_dvb_s2_buf ( uint8_t *  buf,
int  len 
)
static

Definition at line 221 of file crsf.cpp.

References crc8_dvb_s2().

Referenced by write_frame_crc().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_config()

int crsf_config ( int  uart_fd)

Configure an UART port to be used for CRSF.

Parameters
uart_fdUART file descriptor
Returns
0 on success, -errno otherwise

Definition at line 147 of file crsf.cpp.

References convert_channel_value(), and CRSF_BAUDRATE.

Referenced by RCInput::cycle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_frame_CRC()

uint8_t crsf_frame_CRC ( const crsf_frame_t frame)

Definition at line 232 of file crsf.cpp.

References crc8_dvb_s2(), crsf_frame_t::header, crsf_frame_header_t::length, crsf_frame_t::payload, and crsf_frame_t::type.

Referenced by crsf_parse_buffer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_parse()

bool crsf_parse ( const uint64_t  now,
const uint8_t *  frame,
unsigned  len,
uint16_t *  values,
uint16_t *  num_values,
uint16_t  max_channels 
)

Parse the CRSF protocol and extract RC channel data.

Parameters
nowcurrent time
framedata to parse
lenlength of frame
valuesoutput channel values, each in range [1000, 2000]
num_valuesset to the number of parsed channels in values
max_channelsmaximum length of values
Returns
true if channels successfully decoded

Definition at line 166 of file crsf.cpp.

References CRSF_DEBUG, crsf_parse_buffer(), current_frame_position, MIN, and unsynced.

Referenced by RCTest::crsfTest(), and RCInput::cycle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_parse_buffer()

◆ crsf_send_telemetry_attitude()

bool crsf_send_telemetry_attitude ( int  uart_fd,
int16_t  pitch,
int16_t  roll,
int16_t  yaw 
)

Send telemetry Attitude information.

Parameters
uart_fdUART file descriptor
pitchPitch angle [rad * 1e4]
rollRoll angle [rad * 1e4]
yawYaw angle [rad * 1e4]
Returns
true on success

Definition at line 478 of file crsf.cpp.

References attitude, write(), write_frame_crc(), write_frame_header(), and write_uint16_t().

Referenced by CRSFTelemetry::send_attitude().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_send_telemetry_battery()

bool crsf_send_telemetry_battery ( int  uart_fd,
uint16_t  voltage,
uint16_t  current,
int  fuel,
uint8_t  remaining 
)

Send telemetry battery information.

Parameters
uart_fdUART file descriptor
voltageVoltage [0.1V]
currentCurrent [0.1A]
fueldrawn mAh
remainingbattery remaining [%]
Returns
true on success

Definition at line 449 of file crsf.cpp.

References battery_sensor, write(), write_frame_crc(), write_frame_header(), write_uint16_t(), write_uint24_t(), and write_uint8_t().

Referenced by CRSFTelemetry::send_battery().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_send_telemetry_flight_mode()

bool crsf_send_telemetry_flight_mode ( int  uart_fd,
const char *  flight_mode 
)

Send telemetry Flight Mode information.

Parameters
uart_fdUART file descriptor
flight_modeFlight Mode string (max length = 15)
Returns
true on success

Definition at line 490 of file crsf.cpp.

References flight_mode, write(), write_frame_crc(), and write_frame_header().

Referenced by CRSFTelemetry::send_flight_mode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ crsf_send_telemetry_gps()

bool crsf_send_telemetry_gps ( int  uart_fd,
int32_t  latitude,
int32_t  longitude,
uint16_t  groundspeed,
uint16_t  gps_heading,
uint16_t  altitude,
uint8_t  num_satellites 
)

Send telemetry GPS information.

Parameters
uart_fdUART file descriptor
latitudelatitude [degree * 1e7]
longitudelongitude [degree * 1e7]
groundspeedGround speed [km/h * 10]
gps_headingGPS heading [degree * 100]
altitudeAltitude [meters + 1000m offset]
num_satellitesnumber of satellites used
Returns
true on success

Definition at line 462 of file crsf.cpp.

References gps, write(), write_frame_crc(), write_frame_header(), write_int32_t(), write_uint16_t(), and write_uint8_t().

Referenced by CRSFTelemetry::send_gps().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_frame_crc()

static void write_frame_crc ( uint8_t *  buf,
int &  offset,
int  buf_size 
)
inlinestatic

Definition at line 440 of file crsf.cpp.

References crc8_dvb_s2_buf(), and write_uint8_t().

Referenced by crsf_send_telemetry_attitude(), crsf_send_telemetry_battery(), crsf_send_telemetry_flight_mode(), and crsf_send_telemetry_gps().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_frame_header()

static void write_frame_header ( uint8_t *  buf,
int &  offset,
crsf_frame_type_t  type,
uint8_t  payload_size 
)
inlinestatic

Definition at line 434 of file crsf.cpp.

References CRSF_SYNC_BYTE, and write_uint8_t().

Referenced by crsf_send_telemetry_attitude(), crsf_send_telemetry_battery(), crsf_send_telemetry_flight_mode(), and crsf_send_telemetry_gps().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_int32_t()

static void write_int32_t ( uint8_t *  buf,
int &  offset,
int32_t  value 
)
inlinestatic

write an int32_t value to a buffer at a given offset and increment the offset

Definition at line 424 of file crsf.cpp.

Referenced by crsf_send_telemetry_gps().

Here is the caller graph for this function:

◆ write_uint16_t()

static void write_uint16_t ( uint8_t *  buf,
int &  offset,
uint16_t  value 
)
inlinestatic

write an uint16_t value to a buffer at a given offset and increment the offset

Definition at line 402 of file crsf.cpp.

Referenced by crsf_send_telemetry_attitude(), crsf_send_telemetry_battery(), and crsf_send_telemetry_gps().

Here is the caller graph for this function:

◆ write_uint24_t()

static void write_uint24_t ( uint8_t *  buf,
int &  offset,
int  value 
)
inlinestatic

write an uint24_t value to a buffer at a given offset and increment the offset

Definition at line 412 of file crsf.cpp.

Referenced by crsf_send_telemetry_battery().

Here is the caller graph for this function:

◆ write_uint8_t()

static void write_uint8_t ( uint8_t *  buf,
int &  offset,
uint8_t  value 
)
inlinestatic

write an uint8_t value to a buffer at a given offset and increment the offset

Definition at line 395 of file crsf.cpp.

Referenced by crsf_send_telemetry_battery(), crsf_send_telemetry_gps(), write_frame_crc(), and write_frame_header().

Here is the caller graph for this function:

Variable Documentation

◆ crsf_frame

crsf_frame_t& crsf_frame = rc_decode_buf.crsf_frame
static

Definition at line 132 of file crsf.cpp.

◆ current_frame_position

unsigned current_frame_position = 0
static

Definition at line 133 of file crsf.cpp.

Referenced by crsf_parse(), and crsf_parse_buffer().

◆ parser_state

Definition at line 134 of file crsf.cpp.

Referenced by sf0x_parser(), and tfmini_parse().