spektrum_rc.cpp
6.69 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file spektrum_rc.cpp
*
* This is a driver for a Spektrum satellite receiver connected to a Snapdragon
* on the serial port. By default port J12 (next to J13, power module side) is used.
*/
#include <string.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/getopt.h>
#include <lib/rc/dsm.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
#include <uORB/topics/input_rc.h>
// Snapdraogon: use J12 (next to J13, power module side)
#define SPEKTRUM_UART_DEVICE_PATH "/dev/tty-3"
#define UNUSED(x) (void)(x)
extern "C" { __EXPORT int spektrum_rc_main(int argc, char *argv[]); }
namespace spektrum_rc
{
volatile bool _task_should_exit = false;
static bool _is_running = false;
static px4_task_t _task_handle = -1;
int start();
int stop();
int info();
void usage();
void task_main(int argc, char *argv[]);
void fill_input_rc(uint16_t raw_rc_count, uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe, unsigned frame_drops, int rssi,
input_rc_s &input_rc);
void task_main(int argc, char *argv[])
{
const char *device_path = SPEKTRUM_UART_DEVICE_PATH;
int ch;
int myoptind = 1;
const char *myoptarg = NULL;
while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'd':
device_path = myoptarg;
break;
default:
break;
}
}
int uart_fd = dsm_init(device_path);
if (uart_fd < 1) {
PX4_ERR("dsm init failed");
return;
}
orb_advert_t rc_pub = nullptr;
// Use a buffer size of the double of the minimum, just to be safe.
uint8_t rx_buf[2 * DSM_BUFFER_SIZE];
_is_running = true;
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS];
uint16_t raw_rc_count = 0;
// Main loop
while (!_task_should_exit) {
int newbytes = ::read(uart_fd, &rx_buf[0], sizeof(rx_buf));
if (newbytes < 0) {
PX4_WARN("read failed");
continue;
}
if (newbytes == 0) {
continue;
}
const hrt_abstime now = hrt_absolute_time();
bool dsm_11_bit;
unsigned frame_drops;
int8_t dsm_rssi;
// parse new data
bool rc_updated = dsm_parse(now, rx_buf, newbytes, &raw_rc_values[0], &raw_rc_count,
&dsm_11_bit, &frame_drops, &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS);
UNUSED(dsm_11_bit);
if (rc_updated) {
input_rc_s input_rc = {};
fill_input_rc(raw_rc_count, raw_rc_values, now, false, false, frame_drops, dsm_rssi,
input_rc);
if (rc_pub == nullptr) {
rc_pub = orb_advertise(ORB_ID(input_rc), &input_rc);
} else {
orb_publish(ORB_ID(input_rc), rc_pub, &input_rc);
}
}
// sleep since no poll for qurt
usleep(10000);
}
orb_unadvertise(rc_pub);
dsm_deinit();
_is_running = false;
}
void fill_input_rc(uint16_t raw_rc_count, uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime now, bool frame_drop, bool failsafe, unsigned frame_drops, int rssi,
input_rc_s &input_rc)
{
input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_QURT;
input_rc.channel_count = raw_rc_count;
if (input_rc.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
input_rc.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
unsigned valid_chans = 0;
for (unsigned i = 0; i < input_rc.channel_count; ++i) {
input_rc.values[i] = raw_rc_values[i];
if (raw_rc_values[i] != UINT16_MAX) {
valid_chans++;
}
}
input_rc.timestamp = now;
input_rc.timestamp_last_signal = input_rc.timestamp;
input_rc.rc_ppm_frame_length = 0;
/* fake rssi if no value was provided */
if (rssi == -1) {
input_rc.rssi = 255;
} else {
input_rc.rssi = rssi;
}
if (valid_chans == 0) {
input_rc.rssi = 0;
}
input_rc.rc_failsafe = failsafe;
input_rc.rc_lost = (valid_chans == 0);
input_rc.rc_lost_frame_count = frame_drops;
input_rc.rc_total_frame_count = 0;
}
int start(int argc, char *argv[])
{
if (_is_running) {
PX4_WARN("already running");
return -1;
}
_task_should_exit = false;
_task_handle = px4_task_spawn_cmd("spektrum_rc_main",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2000,
(px4_main_t)&task_main,
(char *const *)argv);
if (_task_handle < 0) {
PX4_ERR("task start failed");
return -1;
}
return 0;
}
int stop()
{
if (!_is_running) {
PX4_WARN("not running");
return -1;
}
_task_should_exit = true;
while (_is_running) {
usleep(200000);
PX4_INFO(".");
}
_task_handle = -1;
return 0;
}
int info()
{
PX4_INFO("running: %s", _is_running ? "yes" : "no");
return 0;
}
void
usage()
{
PX4_INFO("Usage: spektrum_rc {start|info|stop}");
}
} // namespace spektrum_rc
int spektrum_rc_main(int argc, char *argv[])
{
int myoptind = 1;
if (argc <= 1) {
spektrum_rc::usage();
return 1;
}
const char *verb = argv[myoptind];
if (!strcmp(verb, "start")) {
return spektrum_rc::start(argc - 1, argv + 1);
}
else if (!strcmp(verb, "stop")) {
return spektrum_rc::stop();
}
else if (!strcmp(verb, "info")) {
return spektrum_rc::info();
}
else {
spektrum_rc::usage();
return 1;
}
}