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

RC protocol definition for Spektrum RC. More...

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

Go to the source code of this file.

Classes

struct  dsm_decode_t
 

Macros

#define DSM_FRAME_SIZE   16
 DSM frame size in bytes. More...
 
#define DSM_FRAME_CHANNELS   7
 Max supported DSM channels per frame. More...
 
#define DSM_MAX_CHANNEL_COUNT   18
 Max channel count of any DSM RC. More...
 
#define DSM_BUFFER_SIZE   (DSM_FRAME_SIZE + DSM_FRAME_SIZE / 2)
 
#define DSM2_BIND_PULSES   3 /* DSM_BIND_START parameter, pulses required to start dsm2 pairing */
 
#define DSMX_BIND_PULSES   7 /* DSM_BIND_START parameter, pulses required to start dsmx pairing */
 
#define DSMX8_BIND_PULSES   9 /* DSM_BIND_START parameter, pulses required to start 8 or more channel dsmx pairing */
 

Typedefs

typedef uint8_t dsm_frame_t[DSM_BUFFER_SIZE]
 DSM dsm frame receive buffer. More...
 
typedef uint8_t dsm_buf_t[DSM_FRAME_SIZE *2]
 
typedef struct dsm_decode_t dsm_decode_t
 

Enumerations

enum  DSM_CMD {
  DSM_CMD_BIND_POWER_DOWN = 0, DSM_CMD_BIND_POWER_UP, DSM_CMD_BIND_SET_RX_OUT, DSM_CMD_BIND_SEND_PULSES,
  DSM_CMD_BIND_REINIT_UART
}
 

Functions

__EXPORT int dsm_init (const char *device)
 Initialize the DSM receive functionality. More...
 
__EXPORT void dsm_deinit (void)
 
__EXPORT void dsm_proto_init (void)
 
__EXPORT int dsm_config (int dsm_fd)
 
__EXPORT bool dsm_input (int dsm_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...
 
__EXPORT 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)
 

Detailed Description

RC protocol definition for Spektrum RC.

Author
Lorenz Meier loren.nosp@m.z@px.nosp@m.4.io

Definition in file dsm.h.

Macro Definition Documentation

◆ DSM2_BIND_PULSES

#define DSM2_BIND_PULSES   3 /* DSM_BIND_START parameter, pulses required to start dsm2 pairing */

Definition at line 90 of file dsm.h.

Referenced by RCInput::cycle(), PX4IO::dsm_bind_ioctl(), PX4IO::ioctl(), and PX4IO::set_update_rate().

◆ DSM_BUFFER_SIZE

#define DSM_BUFFER_SIZE   (DSM_FRAME_SIZE + DSM_FRAME_SIZE / 2)

Definition at line 54 of file dsm.h.

Referenced by spektrum_rc::task_main().

◆ DSM_FRAME_CHANNELS

#define DSM_FRAME_CHANNELS   7

Max supported DSM channels per frame.

Definition at line 52 of file dsm.h.

Referenced by dsm_decode(), and dsm_guess_format().

◆ DSM_FRAME_SIZE

#define DSM_FRAME_SIZE   16

DSM frame size in bytes.

Definition at line 51 of file dsm.h.

Referenced by dsm_parse().

◆ DSM_MAX_CHANNEL_COUNT

#define DSM_MAX_CHANNEL_COUNT   18

Max channel count of any DSM RC.

Definition at line 53 of file dsm.h.

Referenced by dsm_decode(), and dsm_proto_init().

◆ DSMX8_BIND_PULSES

#define DSMX8_BIND_PULSES   9 /* DSM_BIND_START parameter, pulses required to start 8 or more channel dsmx pairing */

◆ DSMX_BIND_PULSES

#define DSMX_BIND_PULSES   7 /* DSM_BIND_START parameter, pulses required to start dsmx pairing */

Definition at line 91 of file dsm.h.

Referenced by RCInput::cycle(), PX4IO::dsm_bind_ioctl(), PX4IO::ioctl(), and PX4IO::set_update_rate().

Typedef Documentation

◆ dsm_buf_t

typedef uint8_t dsm_buf_t[DSM_FRAME_SIZE *2]

Definition at line 59 of file dsm.h.

◆ dsm_decode_t

typedef struct dsm_decode_t dsm_decode_t

◆ dsm_frame_t

typedef uint8_t dsm_frame_t[DSM_BUFFER_SIZE]

DSM dsm frame receive buffer.

Definition at line 58 of file dsm.h.

Enumeration Type Documentation

◆ DSM_CMD

enum DSM_CMD
Enumerator
DSM_CMD_BIND_POWER_DOWN 
DSM_CMD_BIND_POWER_UP 
DSM_CMD_BIND_SET_RX_OUT 
DSM_CMD_BIND_SEND_PULSES 
DSM_CMD_BIND_REINIT_UART 

Definition at line 82 of file dsm.h.

Function Documentation

◆ dsm_config()

__EXPORT int dsm_config ( int  dsm_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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dsm_deinit()

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

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dsm_init()

__EXPORT int dsm_init ( const char *  device)

Initialize the DSM receive functionality.

Open the UART for receiving DSM frames and configure it appropriately

Parameters
[in]deviceDevice 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dsm_input()

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

Parameters
[out]valuespointer to per channel array of decoded values
[out]num_valuespointer to number of raw channel values returned, high order bit 0:10 bit data, 1:11 bit data
[out]n_butesnumber of bytes read
[out]bytespointer to the buffer of read bytes
[out]rssivalue in percent, if supported, or 127
Returns
true=decoded raw channel values updated, false=no update

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

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dsm_parse()

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

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dsm_proto_init()

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

Here is the caller graph for this function: