APM:Libraries
RC_DSM_parser.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 
6 #pragma GCC optimize ("O2")
7 
8 #include <AP_HAL/HAL.h>
9 
10 #include <exti.h>
11 #include <timer.h>
12 #include "RCInput.h"
13 #include <pwm_in.h>
14 #include <AP_HAL/utility/dsm.h>
15 #include <AP_HAL/utility/sumd.h>
16 #include "sbus.h"
17 #include "GPIO.h"
18 #include "ring_buffer_pulse.h"
19 
20 #include "RC_DSM_parser.h"
21 
22 using namespace F4Light;
23 
24 
25 extern const AP_HAL::HAL& hal;
26 
27 
28 #if defined(BOARD_DSM_USART)
29 UARTDriver DSM_parser::uartSDriver(BOARD_DSM_USART); // UART connected to DSM pin
30 #endif
31 
32 
33 
34 void DSM_parser::init(uint8_t ch) {
35 #if defined(BOARD_SPEKTRUM_RX_PIN)
36 
37  memset((void *)&_val[0], 0, sizeof(_val));
38  memset((void *)&dsm, 0, sizeof(dsm));
39 
40  _last_signal=0;
41  _last_change =0;
42 
44  if( (sig & ~DSM_BIND_SIGN_MASK) == DSM_BIND_SIGNATURE) {
47  }
48 
50  #ifdef BOARD_SPEKTRUM_PWR_PIN
53  #endif
54 
56 
57  uartSDriver.end(); // just for case
58 
59  // initialize DSM UART
60  uartSDriver.begin(115200);
63 }
64 
65 /*
66  add some bytes of input in DSM serial stream format, coping with partial packets - UART input callback
67  */
69  if(_ioc) {
71  }
72 }
73 
75 
76  while(uartSDriver.available()){
77 
78  // at least 1 byte we have
79  const uint8_t dsm_frame_size = sizeof(dsm.frame);
80 
81  uint32_t now = AP_HAL::millis();
82  if (now - dsm.last_input_ms > 5) {
83  // resync based on time
85  }
86  dsm.last_input_ms = now;
87 
88  if (dsm.partial_frame_count + 1 > dsm_frame_size) {
89  return; // we can't add bytes to buffer
90  }
91 
92 
93  char c= uartSDriver.read();
94 
95  if(state != S_DSM) { // try to decode SUMD data
96  uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
97  uint8_t rssi;
98  uint8_t rx_count;
99  uint16_t channel_count;
100 
101  if (sumd_decode(c, &rssi, &rx_count, &channel_count, values, F4Light_RC_INPUT_NUM_CHANNELS) == 0) {
102  if (channel_count > F4Light_RC_INPUT_NUM_CHANNELS) {
103  continue;
104  }
105  state=S_SUMD;
106  for (uint8_t i=0; i<channel_count; i++) {
107  if (values[i] != 0) {
108  if(_val[i] != values[i]) _last_change = systick_uptime();
109  _val[i] = values[i];
110  }
111  }
112  _channels = channel_count + 1;
114  _val[channel_count] = rssi; // say about RSSI in last channel
115  }
116  }
117 
118  if(state!=S_SUMD) {
121 
122  if (dsm.partial_frame_count == dsm_frame_size) {
124  uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS] {};
125  uint16_t num_values=0;
126  if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) &&
127  num_values >= 5 && num_values <F4Light_RC_INPUT_NUM_CHANNELS) {
128  state=S_DSM;
129  for (uint8_t i=0; i<num_values; i++) {
130  if (values[i] != 0) {
131  if(_val[i] != values[i]) _last_change = systick_uptime();
132  _val[i] = values[i];
133  }
134  }
135  /*
136  the apparent number of channels can change on DSM,
137  as they are spread across multiple frames. We just
138  use the max num_values we get
139  */
140  uint8_t nc = num_values+1;
141  if (nc > _channels) {
142  _channels = nc;
143  }
144 /*
145  DSM frame from datasheet:
146 typedef stuct {
147  UINT8 fades;
148  UINT8 system;
149  UINT16 servo[7];
150 } INT_REMOTE_STR;
151 
152 so we get RSSI from 1st byte and store it to last channel
153 */
154  _val[_channels-1] = dsm.frame[0];
155 
157  }
158  }
159  }
160  }
161 #endif // defined(BOARD_SPEKTRUM_RX_PIN)
162 }
163 
164 
165 
166 #ifdef BOARD_SPEKTRUM_RX_PIN
167 void DSM_parser::_rc_bind(uint16_t dsmMode){
168 /*
169 To put a receiver into bind mode, within 200ms of power application the host device needs to issue a
170 series of falling pulses. The number of pulses issued selects which bind types will be accepted from
171 the transmitter. Selecting the 11ms mode automatically allows either 11ms or 22ms protocols to be
172 used. Selecting DSMX will automatically allow DSM2 to be used if the transmitter is unable to
173 support DSMX. For this reason, we recommend that 11ms DSMX be used (9 (“internal”) or 10
174 (“external”) pulses).
175 DSMX Bind Modes:
176 Pulses Mode Protocol Type
177 7 Internal DSMx 22ms
178 8 External DSMx 22ms
179 9 Internal DSMx 11ms
180 10 External DSMx 11ms
181 
182 see https://github.com/SpektrumFPV/SpektrumDocumentation/blob/master/Telemetry/Remote%20Receiver%20Interfacing.pdf
183 
184 */
185 
186 
187  Scheduler::_delay(72);
188 
189  for (int i = 0; i < dsmMode; i++) { /*Pulse RX pin a number of times*/
194  }
195 
196  Scheduler::_delay(50);
197 }
198 
199 
200 
201 bool DSM_parser::bind(int dsmMode) const {
202 #ifdef BOARD_SPEKTRUM_PWR_PIN
203  uartSDriver.end();
204 
205  GPIO::_write(BOARD_SPEKTRUM_PWR_PIN, BOARD_SPEKTRUM_PWR_OFF); /* power down DSM satellite */
206 
207  Scheduler::_delay(500);
208 
209 
210  GPIO::_write(BOARD_SPEKTRUM_PWR_PIN, BOARD_SPEKTRUM_PWR_ON); /* power up DSM satellite*/
211 
212  GPIO::_pinMode(BOARD_SPEKTRUM_RX_PIN, OUTPUT); /*Set UART RX pin to active output mode*/
213 
214  _rc_bind(dsmMode);
215 
216  uartSDriver.begin(115200); /*Restore USART RX pin to RS232 receive mode*/
217 
218 #else
219  // store request to bing in BACKUP RAM
221 
222 #endif
223  return true;
224 }
225 
226 #endif // BOARD_SPEKTRUM_RX_PIN
AP_HAL::MemberProc mp
Definition: handler.h:18
enum DSM_STATE state
Definition: RC_DSM_parser.h:37
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
#define BOARD_SPEKTRUM_PWR_OFF
Definition: board.h:58
Handler h
Definition: handler.h:20
#define RTC_DSM_BIND_REG
Definition: boards.h:313
#define BOARD_DSM_USART
Definition: board.h:53
Simple circular buffer for PEM input.
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
Definition: GPIO.h:35
#define BOARD_SPEKTRUM_PWR_PIN
Definition: board.h:56
void begin(uint32_t b)
Definition: UARTDriver.h:31
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Definition: sumd.cpp:137
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
timer interface.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void setCallback(Handler cb)
Definition: UARTDriver.h:45
#define DSM_BIND_SIGN_MASK
Definition: boards.h:297
static void _rc_bind(uint16_t dsmMode)
int16_t read() override
Definition: UARTDriver.cpp:103
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define BOARD_SPEKTRUM_PWR_ON
Definition: board.h:57
uint32_t millis()
Definition: system.cpp:157
uint64_t micros64()
Definition: system.cpp:162
bool dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
Definition: dsm.cpp:195
static void do_io_completion(uint8_t id)
Definition: Scheduler.h:422
static UARTDriver uartSDriver
Definition: RC_DSM_parser.h:25
void init(uint8_t ch)
uint32_t available() override
Definition: UARTDriver.cpp:94
volatile uint8_t _channels
Definition: RC_parser.h:24
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS]
Definition: RC_parser.h:22
volatile uint64_t _last_signal
Definition: RC_parser.h:21
static void _delay(uint16_t ms)
Definition: Scheduler.cpp:258
uint32_t board_get_rtc_register(uint16_t reg)
Definition: boards.cpp:151
void board_set_rtc_register(uint32_t sig, uint16_t reg)
Definition: boards.cpp:141
#define F4Light_RC_INPUT_NUM_CHANNELS
Definition: Config.h:12
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static void _delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:305
struct F4Light::DSM_parser::DSM dsm
bool bind(int dsmMode) const override
#define BOARD_SPEKTRUM_RX_PIN
Definition: board.h:55
#define DSM_BIND_SIGNATURE
Definition: boards.h:296
uint64_t _last_change
Definition: RC_parser.h:23
static uint8_t register_io_completion(Handler handle)
Definition: Scheduler.cpp:1219