PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Serial protocol decoder for the Spektrum DSM* family of protocols. More...
#include <px4_platform_common/px4_config.h>
#include <board_config.h>
#include <px4_platform_common/defines.h>
#include <fcntl.h>
#include <unistd.h>
#include <termios.h>
#include <string.h>
#include "dsm.h"
#include "spektrum_rssi.h"
#include "common_rc.h"
#include <drivers/drv_hrt.h>
Go to the source code of this file.
Macros | |
#define | dsm_udelay(arg) px4_usleep(arg) |
Enumerations | |
enum | DSM_DECODE_STATE { DSM_DECODE_STATE_DESYNC = 0, DSM_DECODE_STATE_SYNC } |
Functions | |
static bool | dsm_decode (hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, unsigned max_values, int8_t *rssi_percent) |
Decode the entire dsm frame (all contained channels) More... | |
static bool | dsm_decode_channel (uint16_t raw, unsigned shift, unsigned *channel, unsigned *value) |
Attempt to decode a single channel raw channel datum. More... | |
static bool | dsm_guess_format (bool reset) |
Attempt to guess if receiving 10 or 11 bit channel values. More... | |
int | dsm_config (int fd) |
void | dsm_proto_init () |
int | dsm_init (const char *device) |
Initialize the DSM receive functionality. More... | |
void | dsm_deinit () |
bool | dsm_input (int fd, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, uint8_t *n_bytes, uint8_t **bytes, int8_t *rssi, unsigned max_values) |
Called periodically to check for input data from the DSM UART. More... | |
bool | dsm_parse (const uint64_t now, const uint8_t *frame, const unsigned len, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, int8_t *rssi_percent, uint16_t max_channels) |
Variables | |
static enum DSM_DECODE_STATE | dsm_decode_state = DSM_DECODE_STATE_DESYNC |
static int | dsm_fd = -1 |
File handle to the DSM UART. More... | |
static hrt_abstime | dsm_last_rx_time |
Timestamp when we last received data. More... | |
static hrt_abstime | dsm_last_frame_time |
Timestamp for start of last valid dsm frame. More... | |
static dsm_frame_t & | dsm_frame = rc_decode_buf.dsm.frame |
DSM_BUFFER_SIZE DSM dsm frame receive buffer. More... | |
static dsm_buf_t & | dsm_buf = rc_decode_buf.dsm.buf |
DSM_BUFFER_SIZE DSM dsm frame receive buffer. More... | |
static uint16_t | dsm_chan_buf [DSM_MAX_CHANNEL_COUNT] |
static unsigned | dsm_partial_frame_count |
Count of bytes received for current dsm frame. More... | |
static unsigned | dsm_channel_shift = 0 |
Channel resolution, 0=unknown, 1=10 bit, 2=11 bit. More... | |
static unsigned | dsm_frame_drops = 0 |
Count of incomplete DSM frames. More... | |
static uint16_t | dsm_chan_count = 0 |
DSM channel count. More... | |
Serial protocol decoder for the Spektrum DSM* family of protocols.
Decodes into the global PPM buffer and updates accordingly.
Definition in file dsm.cpp.
#define dsm_udelay | ( | arg | ) | px4_usleep(arg) |
Definition at line 60 of file dsm.cpp.
Referenced by dsm_deinit().
enum DSM_DECODE_STATE |
int dsm_config | ( | int | fd | ) |
Definition at line 240 of file dsm.cpp.
References dsm_guess_format(), dsm_last_rx_time, dsm_partial_frame_count, and hrt_absolute_time().
Referenced by RCInput::cycle(), and dsm_init().
|
static |
Decode the entire dsm frame (all contained channels)
[in] | frame_time | timestamp when this dsm frame was received. Used to detect RX loss in order to reset 10/11 bit guess. |
[out] | values | pointer to per channel array of decoded values |
[out] | num_values | pointer to number of raw channel values returned |
Definition at line 388 of file dsm.cpp.
References dsm_channel_shift, dsm_decode_channel(), dsm_frame, DSM_FRAME_CHANNELS, dsm_guess_format(), dsm_last_frame_time, DSM_MAX_CHANNEL_COUNT, and spek_dbm_to_percent().
Referenced by dsm_parse().
|
static |
Attempt to decode a single channel raw channel datum.
The DSM* protocol doesn't provide any explicit framing, so we detect dsm frame boundaries by the inter-dsm frame delay.
The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps dsm frame transmission time is ~1.4ms.
We expect to only be called when bytes arrive for processing, and if an interval of more than 5ms passes between calls, the first byte we read will be the first byte of a dsm frame.
In the case where byte(s) are dropped from a dsm frame, this also provides a degree of protection. Of course, it would be better if we didn't drop bytes...
Upon receiving a full dsm frame we attempt to decode it
[in] | raw | 16 bit raw channel value from dsm frame |
[in] | shift | position of channel number in raw data |
[out] | channel | pointer to returned channel number |
[out] | value | pointer to returned channel value |
Definition at line 112 of file dsm.cpp.
Referenced by dsm_decode(), and dsm_guess_format().
void dsm_deinit | ( | void | ) |
Definition at line 313 of file dsm.cpp.
References DSM_CMD_BIND_POWER_DOWN, DSM_CMD_BIND_POWER_UP, DSM_CMD_BIND_REINIT_UART, DSM_CMD_BIND_SEND_PULSES, DSM_CMD_BIND_SET_RX_OUT, dsm_fd, dsm_guess_format(), and dsm_udelay.
Referenced by spektrum_rc::task_main(), and RCInput::~RCInput().
|
static |
Attempt to guess if receiving 10 or 11 bit channel values.
[in] | reset | true=reset the 10/11 bit state to unknown |
Definition at line 135 of file dsm.cpp.
References dsm_channel_shift, dsm_decode_channel(), dsm_frame, and DSM_FRAME_CHANNELS.
Referenced by dsm_config(), dsm_decode(), and dsm_deinit().
int dsm_init | ( | const char * | device | ) |
Initialize the DSM receive functionality.
Open the UART for receiving DSM frames and configure it appropriately
[in] | device | Device name of DSM UART |
Definition at line 293 of file dsm.cpp.
References dsm_config(), dsm_fd, and dsm_proto_init().
Referenced by controls_init(), RCInput::init(), and spektrum_rc::task_main().
bool dsm_input | ( | int | fd, |
uint16_t * | values, | ||
uint16_t * | num_values, | ||
bool * | dsm_11_bit, | ||
uint8_t * | n_bytes, | ||
uint8_t ** | bytes, | ||
int8_t * | rssi, | ||
unsigned | max_values | ||
) |
Called periodically to check for input data from the DSM UART.
The DSM* protocol doesn't provide any explicit framing, so we detect dsm frame boundaries by the inter-dsm frame delay. The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps dsm frame transmission time is ~1.4ms. We expect to only be called when bytes arrive for processing, and if an interval of more than 5ms passes between calls, the first byte we read will be the first byte of a dsm frame. In the case where byte(s) are dropped from a dsm frame, this also provides a degree of protection. Of course, it would be better if we didn't drop bytes... Upon receiving a full dsm frame we attempt to decode it.
[out] | values | pointer to per channel array of decoded values |
[out] | num_values | pointer to number of raw channel values returned, high order bit 0:10 bit data, 1:11 bit data |
[out] | n_butes | number of bytes read |
[out] | bytes | pointer to the buffer of read bytes |
[out] | rssi | value in percent, if supported, or 127 |
Definition at line 593 of file dsm.cpp.
References dsm_buf, dsm_frame_drops, dsm_parse(), hrt_absolute_time(), hrt_abstime, and read().
Referenced by dsm_port_input().
bool dsm_parse | ( | const uint64_t | now, |
const uint8_t * | frame, | ||
const unsigned | len, | ||
uint16_t * | values, | ||
uint16_t * | num_values, | ||
bool * | dsm_11_bit, | ||
unsigned * | frame_drops, | ||
int8_t * | rssi_percent, | ||
uint16_t | max_channels | ||
) |
Definition at line 640 of file dsm.cpp.
References dsm_chan_buf, dsm_chan_count, dsm_decode(), dsm_decode_state, DSM_DECODE_STATE_DESYNC, DSM_DECODE_STATE_SYNC, dsm_frame, dsm_frame_drops, DSM_FRAME_SIZE, dsm_last_rx_time, and dsm_partial_frame_count.
Referenced by RCInput::cycle(), dsm_input(), RCTest::dsmTest(), and spektrum_rc::task_main().
void dsm_proto_init | ( | void | ) |
Definition at line 273 of file dsm.cpp.
References dsm_chan_buf, dsm_chan_count, dsm_channel_shift, dsm_decode_state, DSM_DECODE_STATE_DESYNC, dsm_frame_drops, and DSM_MAX_CHANNEL_COUNT.
Referenced by dsm_init(), and RCTest::dsmTest().
|
static |
DSM_BUFFER_SIZE DSM dsm frame receive buffer.
Definition at line 74 of file dsm.cpp.
Referenced by dsm_input().
|
static |
Definition at line 76 of file dsm.cpp.
Referenced by dsm_parse(), and dsm_proto_init().
|
static |
DSM channel count.
Definition at line 80 of file dsm.cpp.
Referenced by dsm_parse(), and dsm_proto_init().
|
static |
Channel resolution, 0=unknown, 1=10 bit, 2=11 bit.
Definition at line 78 of file dsm.cpp.
Referenced by dsm_decode(), dsm_guess_format(), and dsm_proto_init().
|
static |
Referenced by dsm_parse(), and dsm_proto_init().
|
static |
File handle to the DSM UART.
Definition at line 70 of file dsm.cpp.
Referenced by dsm_deinit(), and dsm_init().
|
static |
DSM_BUFFER_SIZE DSM dsm frame receive buffer.
Definition at line 73 of file dsm.cpp.
Referenced by dsm_decode(), dsm_guess_format(), and dsm_parse().
|
static |
Count of incomplete DSM frames.
Definition at line 79 of file dsm.cpp.
Referenced by dsm_input(), dsm_parse(), dsm_proto_init(), and RCTest::dsmTest().
|
static |
Timestamp for start of last valid dsm frame.
Definition at line 72 of file dsm.cpp.
Referenced by dsm_decode().
|
static |
Timestamp when we last received data.
Definition at line 71 of file dsm.cpp.
Referenced by dsm_config(), and dsm_parse().
|
static |
Count of bytes received for current dsm frame.
Definition at line 77 of file dsm.cpp.
Referenced by dsm_config(), and dsm_parse().