PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <px4_platform_common/px4_config.h>
#include <fcntl.h>
#include <unistd.h>
#include <termios.h>
#include <string.h>
#include "sbus.h"
#include "common_rc.h"
#include <drivers/drv_hrt.h>
Go to the source code of this file.
Classes | |
struct | sbus_bit_pick |
Macros | |
#define | SBUS_DEBUG_LEVEL 0 /* Set debug output level */ |
#define | SBUS_START_SYMBOL 0x0f |
#define | SBUS_INPUT_CHANNELS 16 |
#define | SBUS_FLAGS_BYTE 23 |
#define | SBUS_FAILSAFE_BIT 3 |
#define | SBUS_FRAMELOST_BIT 2 |
#define | SBUS1_MAX_RATE_HZ 300 |
#define | SBUS1_MIN_RATE_HZ 50 |
#define | SBUS1_DEFAULT_RATE_HZ 72 |
#define | SBUS_RANGE_MIN 200.0f |
#define | SBUS_RANGE_MAX 1800.0f |
#define | SBUS_TARGET_MIN 1000.0f |
#define | SBUS_TARGET_MAX 2000.0f |
#define | SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN)) |
#define | SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f)) |
#define | SBUS2_FRAME_SIZE_RX_VOLTAGE 3 |
#define | SBUS2_FRAME_SIZE_GPS_DIGIT 3 |
Enumerations | |
enum | SBUS2_DECODE_STATE { SBUS2_DECODE_STATE_DESYNC = 0xFFF, SBUS2_DECODE_STATE_SBUS_START = 0x2FF, SBUS2_DECODE_STATE_SBUS1_SYNC = 0x00, SBUS2_DECODE_STATE_SBUS2_SYNC = 0x1FF, SBUS2_DECODE_STATE_SBUS2_RX_VOLTAGE = 0x04, SBUS2_DECODE_STATE_SBUS2_GPS = 0x14, SBUS2_DECODE_STATE_SBUS2_DATA1 = 0x24, SBUS2_DECODE_STATE_SBUS2_DATA2 = 0x34 } |
Functions | |
unsigned | sbus_dropped_frames () |
The number of incomplete frames we encountered. More... | |
static bool | sbus_decode (uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values) |
int | sbus_init (const char *device, bool singlewire) |
int | sbus_config (int sbus_fd, bool singlewire) |
Parse serial bytes on the S.BUS bus. More... | |
void | sbus1_output (int sbus_fd, uint16_t *values, uint16_t num_values) |
void | sbus2_output (int sbus_fd, uint16_t *values, uint16_t num_values) |
bool | sbus_input (int sbus_fd, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels) |
bool | sbus_parse (uint64_t now, uint8_t *frame, unsigned len, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, unsigned *frame_drops, uint16_t max_channels) |
void | sbus1_set_output_rate_hz (uint16_t rate_hz) |
Variables | |
static hrt_abstime | last_rx_time |
static hrt_abstime | last_txframe_time = 0 |
static enum SBUS2_DECODE_STATE | sbus_decode_state = SBUS2_DECODE_STATE_DESYNC |
static sbus_frame_t & | sbus_frame = rc_decode_buf.sbus_frame |
static unsigned | partial_frame_count |
static unsigned | sbus1_frame_delay = (1000U * 1000U) / SBUS1_DEFAULT_RATE_HZ |
static unsigned | sbus_frame_drops |
static const struct sbus_bit_pick | sbus_decoder [SBUS_INPUT_CHANNELS][3] |
#define SBUS1_MAX_RATE_HZ 300 |
Definition at line 75 of file sbus.cpp.
Referenced by sbus1_set_output_rate_hz().
#define SBUS1_MIN_RATE_HZ 50 |
Definition at line 76 of file sbus.cpp.
Referenced by sbus1_set_output_rate_hz().
#define SBUS2_FRAME_SIZE_RX_VOLTAGE 3 |
Definition at line 106 of file sbus.cpp.
Referenced by sbus_parse().
#define SBUS_FAILSAFE_BIT 3 |
Definition at line 68 of file sbus.cpp.
Referenced by sbus_decode().
#define SBUS_FLAGS_BYTE 23 |
Definition at line 67 of file sbus.cpp.
Referenced by sbus_decode().
#define SBUS_FRAMELOST_BIT 2 |
Definition at line 69 of file sbus.cpp.
Referenced by sbus_decode().
#define SBUS_INPUT_CHANNELS 16 |
Definition at line 66 of file sbus.cpp.
Referenced by sbus_decode().
#define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN)) |
Definition at line 100 of file sbus.cpp.
Referenced by sbus1_output(), and sbus_decode().
#define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f)) |
Definition at line 101 of file sbus.cpp.
Referenced by sbus1_output(), and sbus_decode().
#define SBUS_START_SYMBOL 0x0f |
Definition at line 64 of file sbus.cpp.
Referenced by sbus_decode(), sbus_input(), and sbus_parse().
enum SBUS2_DECODE_STATE |
void sbus1_output | ( | int | sbus_fd, |
uint16_t * | values, | ||
uint16_t | num_values | ||
) |
Definition at line 237 of file sbus.cpp.
References f(), hrt_absolute_time(), hrt_abstime, last_txframe_time, sbus1_frame_delay, SBUS_FRAME_SIZE, SBUS_SCALE_FACTOR, SBUS_SCALE_OFFSET, and write().
Referenced by mixer_tick(), and sbus2_output().
void sbus1_set_output_rate_hz | ( | uint16_t | rate_hz | ) |
Definition at line 705 of file sbus.cpp.
References sbus1_frame_delay, SBUS1_MAX_RATE_HZ, and SBUS1_MIN_RATE_HZ.
Referenced by registers_set_one().
void sbus2_output | ( | int | sbus_fd, |
uint16_t * | values, | ||
uint16_t | num_values | ||
) |
Definition at line 276 of file sbus.cpp.
References sbus1_output().
Referenced by mixer_tick().
int sbus_config | ( | int | sbus_fd, |
bool | singlewire | ||
) |
Parse serial bytes on the S.BUS bus.
The S.bus protocol doesn't provide reliable framing, so we detect frame boundaries by the inter-frame delay.
The minimum frame spacing is 7ms; with 25 bytes at 100000bps frame transmission time is ~2ms.
If an interval of more than 4ms (7 ms frame spacing plus margin) passes between calls, the first byte we read will be the first byte of a frame.
In the case where byte(s) are dropped from a frame, this also provides a degree of protection. Of course, it would be better if we didn't drop bytes...
Definition at line 153 of file sbus.cpp.
References hrt_absolute_time(), last_rx_time, partial_frame_count, and sbus_frame_drops.
Referenced by RCInput::cycle(), RCInput::init(), and sbus_init().
|
static |
Definition at line 584 of file sbus.cpp.
References sbus_bit_pick::byte, decode(), f(), sbus_bit_pick::lshift, sbus_bit_pick::mask, sbus_bit_pick::rshift, SBUS2_DECODE_STATE_DESYNC, SBUS2_DECODE_STATE_SBUS1_SYNC, SBUS2_DECODE_STATE_SBUS2_GPS, SBUS2_DECODE_STATE_SBUS2_RX_VOLTAGE, SBUS2_DECODE_STATE_SBUS2_SYNC, sbus_decode_state, SBUS_FAILSAFE_BIT, SBUS_FLAGS_BYTE, sbus_frame_drops, SBUS_FRAME_SIZE, SBUS_FRAMELOST_BIT, SBUS_INPUT_CHANNELS, SBUS_SCALE_FACTOR, SBUS_SCALE_OFFSET, and SBUS_START_SYMBOL.
Referenced by sbus_dropped_frames(), and sbus_parse().
unsigned sbus_dropped_frames | ( | void | ) |
The number of incomplete frames we encountered.
Definition at line 128 of file sbus.cpp.
References sbus_decode(), and sbus_frame_drops.
Referenced by RCInput::print_status().
int sbus_init | ( | const char * | device, |
bool | singlewire | ||
) |
Definition at line 138 of file sbus.cpp.
References sbus_config().
Referenced by controls_init().
bool sbus_input | ( | int | sbus_fd, |
uint16_t * | values, | ||
uint16_t * | num_values, | ||
bool * | sbus_failsafe, | ||
bool * | sbus_frame_drop, | ||
uint16_t | max_channels | ||
) |
Definition at line 282 of file sbus.cpp.
References hrt_absolute_time(), hrt_abstime, last_rx_time, partial_frame_count, read(), SBUS2_DECODE_STATE_DESYNC, sbus_decode_state, sbus_frame_drops, SBUS_FRAME_SIZE, sbus_parse(), and SBUS_START_SYMBOL.
Referenced by controls_tick().
bool sbus_parse | ( | uint64_t | now, |
uint8_t * | frame, | ||
unsigned | len, | ||
uint16_t * | values, | ||
uint16_t * | num_values, | ||
bool * | sbus_failsafe, | ||
bool * | sbus_frame_drop, | ||
unsigned * | frame_drops, | ||
uint16_t | max_channels | ||
) |
Definition at line 343 of file sbus.cpp.
References last_rx_time, partial_frame_count, SBUS2_DECODE_STATE_DESYNC, SBUS2_DECODE_STATE_SBUS1_SYNC, SBUS2_DECODE_STATE_SBUS2_GPS, SBUS2_DECODE_STATE_SBUS2_RX_VOLTAGE, SBUS2_DECODE_STATE_SBUS2_SYNC, SBUS2_DECODE_STATE_SBUS_START, SBUS2_FRAME_SIZE_RX_VOLTAGE, sbus_decode(), sbus_decode_state, sbus_frame, sbus_frame_drops, SBUS_FRAME_SIZE, and SBUS_START_SYMBOL.
Referenced by RCInput::cycle(), RCTest::sbus2Test(), and sbus_input().
|
static |
Definition at line 103 of file sbus.cpp.
Referenced by sbus_config(), sbus_input(), and sbus_parse().
|
static |
Definition at line 104 of file sbus.cpp.
Referenced by sbus1_output().
|
static |
Definition at line 122 of file sbus.cpp.
Referenced by sbus_config(), sbus_input(), and sbus_parse().
|
static |
Definition at line 123 of file sbus.cpp.
Referenced by sbus1_output(), and sbus1_set_output_rate_hz().
|
static |
Referenced by sbus_decode(), sbus_input(), and sbus_parse().
|
static |
|
static |
Definition at line 120 of file sbus.cpp.
Referenced by sbus_parse().
|
static |
Definition at line 125 of file sbus.cpp.
Referenced by RCTest::sbus2Test(), sbus_config(), sbus_decode(), sbus_dropped_frames(), sbus_input(), and sbus_parse().