PX4 Firmware
PX4 Autopilot Software http://px4.io
|
RC protocol definition for CSRF (TBS Crossfire). More...
#include <stdint.h>
#include <px4_platform_common/defines.h>
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... | |
RC protocol definition for CSRF (TBS Crossfire).
It is an uninverted protocol at 420000 baudrate.
RC channels come in at 150Hz.
Definition in file crsf.h.
#define CRSF_PAYLOAD_SIZE_MAX (CRSF_FRAME_SIZE_MAX-4) |
__EXPORT int crsf_config | ( | int | uart_fd | ) |
Configure an UART port to be used for CRSF.
uart_fd | UART file descriptor |
Definition at line 147 of file crsf.cpp.
References convert_channel_value(), and CRSF_BAUDRATE.
Referenced by RCInput::cycle().
__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.
now | current time |
frame | data to parse |
len | length of frame |
values | output channel values, each in range [1000, 2000] |
num_values | set to the number of parsed channels in values |
max_channels | maximum length of values |
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().
__EXPORT bool crsf_send_telemetry_attitude | ( | int | uart_fd, |
int16_t | pitch, | ||
int16_t | roll, | ||
int16_t | yaw | ||
) |
Send telemetry Attitude information.
uart_fd | UART file descriptor |
pitch | Pitch angle [rad * 1e4] |
roll | Roll angle [rad * 1e4] |
yaw | Yaw angle [rad * 1e4] |
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().
__EXPORT bool crsf_send_telemetry_battery | ( | int | uart_fd, |
uint16_t | voltage, | ||
uint16_t | current, | ||
int | fuel, | ||
uint8_t | remaining | ||
) |
Send telemetry battery information.
uart_fd | UART file descriptor |
voltage | Voltage [0.1V] |
current | Current [0.1A] |
fuel | drawn mAh |
remaining | battery remaining [%] |
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().
__EXPORT bool crsf_send_telemetry_flight_mode | ( | int | uart_fd, |
const char * | flight_mode | ||
) |
Send telemetry Flight Mode information.
uart_fd | UART file descriptor |
flight_mode | Flight Mode string (max length = 15) |
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().
__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.
uart_fd | UART file descriptor |
latitude | latitude [degree * 1e7] |
longitude | longitude [degree * 1e7] |
groundspeed | Ground speed [km/h * 10] |
gps_heading | GPS heading [degree * 100] |
altitude | Altitude [meters + 1000m offset] |
num_satellites | number of satellites used |
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().