PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <drivers/drv_hrt.h>
#include <termios.h>
#include <string.h>
#include <unistd.h>
#include "crsf.h"
#include "common_rc.h"
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 |
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_t & | crsf_frame = rc_decode_buf.crsf_frame |
static unsigned | current_frame_position = 0 |
static crsf_parser_state_t | parser_state = crsf_parser_state_t::unsynced |
#define CRSF_BAUDRATE 420000 |
Definition at line 58 of file crsf.cpp.
Referenced by crsf_config().
#define CRSF_DEBUG | ( | ... | ) |
Definition at line 37 of file crsf.cpp.
Referenced by crsf_parse(), and crsf_parse_buffer().
#define CRSF_SYNC_BYTE 0xC8 |
Definition at line 60 of file crsf.cpp.
Referenced by write_frame_header().
#define CRSF_VERBOSE | ( | ... | ) |
Definition at line 43 of file crsf.cpp.
Referenced by crsf_parse_buffer().
#define MIN | ( | a, | |
b | |||
) | (((a)<(b))?(a):(b)) |
Definition at line 54 of file crsf.cpp.
Referenced by crsf_parse(), and crsf_parse_buffer().
|
strong |
|
strong |
|
strong |
|
strong |
|
static |
Convert from RC to PWM value.
chan_value | channel value in [172, 1811] |
Definition at line 244 of file crsf.cpp.
References f().
Referenced by crsf_config(), and crsf_parse_buffer().
|
static |
Definition at line 205 of file crsf.cpp.
Referenced by crc8_dvb_s2_buf(), and crsf_frame_CRC().
|
static |
Definition at line 221 of file crsf.cpp.
References crc8_dvb_s2().
Referenced by write_frame_crc().
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().
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().
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().
|
static |
parse the current crsf_frame buffer
Definition at line 257 of file crsf.cpp.
References crsf_payload_RC_channels_packed_t::chan0, crsf_payload_RC_channels_packed_t::chan1, crsf_payload_RC_channels_packed_t::chan10, crsf_payload_RC_channels_packed_t::chan11, crsf_payload_RC_channels_packed_t::chan12, crsf_payload_RC_channels_packed_t::chan13, crsf_payload_RC_channels_packed_t::chan14, crsf_payload_RC_channels_packed_t::chan15, crsf_payload_RC_channels_packed_t::chan2, crsf_payload_RC_channels_packed_t::chan3, crsf_payload_RC_channels_packed_t::chan4, crsf_payload_RC_channels_packed_t::chan5, crsf_payload_RC_channels_packed_t::chan6, crsf_payload_RC_channels_packed_t::chan7, crsf_payload_RC_channels_packed_t::chan8, crsf_payload_RC_channels_packed_t::chan9, convert_channel_value(), CRSF_DEBUG, crsf_frame_CRC(), CRSF_VERBOSE, current_frame_position, crsf_frame_t::header, crsf_frame_header_t::length, MIN, crsf_frame_t::payload, rc_channels, rc_channels_packed, synced, crsf_frame_t::type, and unsynced.
Referenced by crsf_parse().
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().
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().
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().
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
static |
|
static |
Definition at line 133 of file crsf.cpp.
Referenced by crsf_parse(), and crsf_parse_buffer().
|
static |
Definition at line 134 of file crsf.cpp.
Referenced by sf0x_parser(), and tfmini_parse().