PX4 Firmware
PX4 Autopilot Software http://px4.io
crsf.h File Reference

RC protocol definition for CSRF (TBS Crossfire). More...

#include <stdint.h>
#include <px4_platform_common/defines.h>
Include dependency graph for crsf.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  crsf_frame_header_t
 
struct  crsf_frame_t
 

Macros

#define CRSF_FRAME_SIZE_MAX   30
 
#define CRSF_PAYLOAD_SIZE_MAX   (CRSF_FRAME_SIZE_MAX-4)
 

Functions

__EXPORT int crsf_config (int uart_fd)
 Configure an UART port to be used for CRSF. More...
 
__EXPORT 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...
 
__EXPORT bool crsf_send_telemetry_battery (int uart_fd, uint16_t voltage, uint16_t current, int fuel, uint8_t remaining)
 Send telemetry battery information. More...
 
__EXPORT 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...
 
__EXPORT bool crsf_send_telemetry_attitude (int uart_fd, int16_t pitch, int16_t roll, int16_t yaw)
 Send telemetry Attitude information. More...
 
__EXPORT bool crsf_send_telemetry_flight_mode (int uart_fd, const char *flight_mode)
 Send telemetry Flight Mode information. More...
 

Detailed Description

RC protocol definition for CSRF (TBS Crossfire).

It is an uninverted protocol at 420000 baudrate.

RC channels come in at 150Hz.

Author
Beat Küng beat-.nosp@m.kuen.nosp@m.g@gmx.nosp@m..net

Definition in file crsf.h.

Macro Definition Documentation

◆ CRSF_FRAME_SIZE_MAX

#define CRSF_FRAME_SIZE_MAX   30

Definition at line 52 of file crsf.h.

◆ CRSF_PAYLOAD_SIZE_MAX

#define CRSF_PAYLOAD_SIZE_MAX   (CRSF_FRAME_SIZE_MAX-4)

Definition at line 53 of file crsf.h.

Function Documentation

◆ crsf_config()

__EXPORT 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_parse()

__EXPORT 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_send_telemetry_attitude()

__EXPORT 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()

__EXPORT 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()

__EXPORT 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()

__EXPORT 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: