PX4 Firmware
PX4 Autopilot Software http://px4.io
RCInput.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #include "RCInput.hpp"
35 
36 #include "crsf_telemetry.h"
37 
38 using namespace time_literals;
39 
40 #if defined(SPEKTRUM_POWER)
41 static bool bind_spektrum(int arg);
42 #endif /* SPEKTRUM_POWER */
43 
44 work_s RCInput::_work = {};
45 constexpr char const *RCInput::RC_SCAN_STRING[];
46 
47 RCInput::RCInput(bool run_as_task, char *device) :
48  _cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")),
49  _publish_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": publish interval"))
50 {
51  // rc input, published to ORB
52  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM;
53 
54  // initialize it as RC lost
55  _rc_in.rc_lost = true;
56 
57  // initialize raw_rc values and count
58  for (unsigned i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; i++) {
59  _raw_rc_values[i] = UINT16_MAX;
60  }
61 
62 #ifdef RC_SERIAL_PORT
63 
64  if (device) {
65  strncpy(_device, device, sizeof(_device));
66  _device[sizeof(_device) - 1] = '\0';
67  }
68 
69 #endif
70 }
71 
73 {
74 #ifdef RC_SERIAL_PORT
75  dsm_deinit();
76 #endif
77 
78  if (_crsf_telemetry) {
79  delete (_crsf_telemetry);
80  }
81 
84 }
85 
86 int
88 {
89 #ifdef RC_SERIAL_PORT
90 
91 # ifdef RF_RADIO_POWER_CONTROL
92  // power radio on
93  RF_RADIO_POWER_CONTROL(true);
94 # endif
95 
96  // dsm_init sets some file static variables and returns a file descriptor
98 
99  if (_rcs_fd < 0) {
100  return -errno;
101  }
102 
103  if (board_rc_swap_rxtx(_device)) {
104  ioctl(_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
105  }
106 
107  // assume SBUS input and immediately switch it to
108  // so that if Single wire mode on TX there will be only
109  // a short contention
110  sbus_config(_rcs_fd, board_rc_singlewire(_device));
111 # ifdef GPIO_PPM_IN
112  // disable CPPM input by mapping it away from the timer capture input
113  px4_arch_unconfiggpio(GPIO_PPM_IN);
114 # endif
115 #endif
116 
117  return 0;
118 }
119 
120 int
121 RCInput::task_spawn(int argc, char *argv[])
122 {
123  bool run_as_task = false;
124  bool error_flag = false;
125 
126  int myoptind = 1;
127  int ch;
128  const char *myoptarg = nullptr;
129  const char *device = RC_SERIAL_PORT;
130 
131  while ((ch = px4_getopt(argc, argv, "td:", &myoptind, &myoptarg)) != EOF) {
132  switch (ch) {
133  case 't':
134  run_as_task = true;
135  break;
136 
137  case 'd':
138  device = myoptarg;
139  break;
140 
141  case '?':
142  error_flag = true;
143  break;
144 
145  default:
146  PX4_WARN("unrecognized flag");
147  error_flag = true;
148  break;
149  }
150  }
151 
152  if (error_flag) {
153  return -1;
154  }
155 
156 
157  if (!run_as_task) {
158 
159  /* schedule a cycle to start things */
160  int ret = work_queue(HPWORK, &_work, (worker_t)&RCInput::cycle_trampoline_init, (void *)device, 0);
161 
162  if (ret < 0) {
163  return ret;
164  }
165 
166  // we need to wait, otherwise 'device' could go out of scope while still being accessed
167  wait_until_running();
168 
169  _task_id = task_id_is_work_queue;
170 
171  } else {
172 
173  /* start the IO interface task */
174 
175  const char *const args[] = { device, nullptr };
176  _task_id = px4_task_spawn_cmd("rc_input",
177  SCHED_DEFAULT,
178  SCHED_PRIORITY_SLOW_DRIVER,
179  1000,
180  (px4_main_t)&run_trampoline,
181  (char *const *)args);
182 
183  if (_task_id < 0) {
184  _task_id = -1;
185  return -errno;
186  }
187  }
188 
189  return PX4_OK;
190 }
191 
192 void
194 {
195  RCInput *dev = new RCInput(false, (char *)arg);
196 
197  if (!dev) {
198  PX4_ERR("alloc failed");
199  return;
200  }
201 
202  int ret = dev->init();
203 
204  if (ret != 0) {
205  PX4_ERR("init failed (%i)", ret);
206  delete dev;
207  return;
208  }
209 
210  _object.store(dev);
211 
212  dev->cycle();
213 }
214 void
216 {
217  RCInput *dev = static_cast<RCInput *>(arg);
218  dev->cycle();
219 }
220 
221 void
222 RCInput::fill_rc_in(uint16_t raw_rc_count_local,
223  uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
224  hrt_abstime now, bool frame_drop, bool failsafe,
225  unsigned frame_drops, int rssi = -1)
226 {
227  // fill rc_in struct for publishing
228  _rc_in.channel_count = raw_rc_count_local;
229 
230  if (_rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
231  _rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
232  }
233 
234  unsigned valid_chans = 0;
235 
236  for (unsigned i = 0; i < _rc_in.channel_count; i++) {
237  _rc_in.values[i] = raw_rc_values_local[i];
238 
239  if (raw_rc_values_local[i] != UINT16_MAX) {
240  valid_chans++;
241  }
242 
243  // once filled, reset values back to default
244  _raw_rc_values[i] = UINT16_MAX;
245  }
246 
247  _rc_in.timestamp = now;
250 
251  /* fake rssi if no value was provided */
252  if (rssi == -1) {
253 
254  /* set RSSI if analog RSSI input is present */
256  float rssi_analog = ((_analog_rc_rssi_volt - 0.2f) / 3.0f) * 100.0f;
257 
258  if (rssi_analog > 100.0f) {
259  rssi_analog = 100.0f;
260  }
261 
262  if (rssi_analog < 0.0f) {
263  rssi_analog = 0.0f;
264  }
265 
266  _rc_in.rssi = rssi_analog;
267 
268  } else {
269  _rc_in.rssi = 255;
270  }
271 
272  } else {
273  _rc_in.rssi = rssi;
274  }
275 
276  if (valid_chans == 0) {
277  _rc_in.rssi = 0;
278  }
279 
280  _rc_in.rc_failsafe = failsafe;
281  _rc_in.rc_lost = (valid_chans == 0);
282  _rc_in.rc_lost_frame_count = frame_drops;
284 }
285 
286 #ifdef RC_SERIAL_PORT
287 void RCInput::set_rc_scan_state(RC_SCAN newState)
288 {
289 // PX4_WARN("RCscan: %s failed, trying %s", RCInput::RC_SCAN_STRING[_rc_scan_state], RCInput::RC_SCAN_STRING[newState]);
290  _rc_scan_begin = 0;
291  _rc_scan_state = newState;
292 }
293 
294 void RCInput::rc_io_invert(bool invert)
295 {
296  // First check if the board provides a board-specific inversion method (e.g. via GPIO),
297  // and if not use an IOCTL
298  if (!board_rc_invert_input(_device, invert)) {
299  ioctl(_rcs_fd, TIOCSINVERT, invert ? (SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX) : 0);
300  }
301 }
302 #endif
303 
304 void
306 {
307  int ret = init();
308 
309  if (ret != 0) {
310  PX4_ERR("init failed (%i)", ret);
311  exit_and_cleanup();
312  return;
313  }
314 
315  cycle();
316 }
317 
318 void
320 {
321  while (true) {
322 
324 
325  const hrt_abstime cycle_timestamp = hrt_absolute_time();
326 
327 #if defined(SPEKTRUM_POWER)
328  /* vehicle command */
329  vehicle_command_s vcmd;
330 
331  if (_vehicle_cmd_sub.update(&vcmd)) {
332  // Check for a pairing command
333  if ((unsigned int)vcmd.command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) {
334  if (!_rc_scan_locked /* !_armed.armed */) { // TODO: add armed check?
335  if ((int)vcmd.param1 == 0) {
336  // DSM binding command
337  int dsm_bind_mode = (int)vcmd.param2;
338 
339  int dsm_bind_pulses = 0;
340 
341  if (dsm_bind_mode == 0) {
342  dsm_bind_pulses = DSM2_BIND_PULSES;
343 
344  } else if (dsm_bind_mode == 1) {
345  dsm_bind_pulses = DSMX_BIND_PULSES;
346 
347  } else {
348  dsm_bind_pulses = DSMX8_BIND_PULSES;
349  }
350 
351  bind_spektrum(dsm_bind_pulses);
352  }
353 
354  } else {
355  PX4_WARN("system armed, bind request rejected");
356  }
357  }
358  }
359 
360 #endif /* SPEKTRUM_POWER */
361 
362  /* update ADC sampling */
363 #ifdef ADC_RC_RSSI_CHANNEL
364  adc_report_s adc;
365 
366  if (_adc_sub.update(&adc)) {
367  const unsigned adc_chans = sizeof(adc.channel_id) / sizeof(adc.channel_id[0]);
368 
369  for (unsigned i = 0; i < adc_chans; i++) {
370  if (adc.channel_id[i] == ADC_RC_RSSI_CHANNEL) {
371 
372  if (_analog_rc_rssi_volt < 0.0f) {
374  }
375 
376  _analog_rc_rssi_volt = _analog_rc_rssi_volt * 0.995f + adc.channel_value[i] * 0.005f;
377 
378  /* only allow this to be used if we see a high RSSI once */
379  if (_analog_rc_rssi_volt > 2.5f) {
380  _analog_rc_rssi_stable = true;
381  }
382  }
383  }
384  }
385 
386 #endif /* ADC_RC_RSSI_CHANNEL */
387 
388  bool rc_updated = false;
389 
390 #ifdef RC_SERIAL_PORT
391  // This block scans for a supported serial RC input and locks onto the first one found
392  // Scan for 300 msec, then switch protocol
393  constexpr hrt_abstime rc_scan_max = 300_ms;
394 
395  bool sbus_failsafe, sbus_frame_drop;
396  unsigned frame_drops;
397  bool dsm_11_bit;
398 
399  if (_report_lock && _rc_scan_locked) {
400  _report_lock = false;
401  //PX4_WARN("RCscan: %s RC input locked", RC_SCAN_STRING[_rc_scan_state]);
402  }
403 
404  int newBytes = 0;
405 
406  if (_run_as_task) {
407  // TODO: needs work (poll _rcs_fd)
408  // int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), 100);
409  // then update priority to SCHED_PRIORITY_FAST_DRIVER
410  // read all available data from the serial RC input UART
411  newBytes = ::read(_rcs_fd, &_rcs_buf[0], SBUS_BUFFER_SIZE);
412 
413  } else {
414  // read all available data from the serial RC input UART
415  newBytes = ::read(_rcs_fd, &_rcs_buf[0], SBUS_BUFFER_SIZE);
416  }
417 
418  switch (_rc_scan_state) {
419  case RC_SCAN_SBUS:
420  if (_rc_scan_begin == 0) {
421  _rc_scan_begin = cycle_timestamp;
422  // Configure serial port for SBUS
423  sbus_config(_rcs_fd, board_rc_singlewire(_device));
424  rc_io_invert(true);
425 
426  } else if (_rc_scan_locked
427  || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
428 
429  // parse new data
430  if (newBytes > 0) {
431  rc_updated = sbus_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count, &sbus_failsafe,
432  &sbus_frame_drop, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
433 
434  if (rc_updated) {
435  // we have a new SBUS frame. Publish it.
436  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SBUS;
437  fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp,
438  sbus_frame_drop, sbus_failsafe, frame_drops);
439  _rc_scan_locked = true;
440  }
441  }
442 
443  } else {
444  // Scan the next protocol
446  }
447 
448  break;
449 
450  case RC_SCAN_DSM:
451  if (_rc_scan_begin == 0) {
452  _rc_scan_begin = cycle_timestamp;
453  // // Configure serial port for DSM
455  rc_io_invert(false);
456 
457  } else if (_rc_scan_locked
458  || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
459 
460  if (newBytes > 0) {
461  int8_t dsm_rssi;
462 
463  // parse new data
464  rc_updated = dsm_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
465  &dsm_11_bit, &frame_drops, &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS);
466 
467  if (rc_updated) {
468  // we have a new DSM frame. Publish it.
469  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_DSM;
470  fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp,
471  false, false, frame_drops, dsm_rssi);
472  _rc_scan_locked = true;
473  }
474  }
475 
476  } else {
477  // Scan the next protocol
479  }
480 
481  break;
482 
483  case RC_SCAN_ST24:
484  if (_rc_scan_begin == 0) {
485  _rc_scan_begin = cycle_timestamp;
486  // Configure serial port for DSM
488  rc_io_invert(false);
489 
490  } else if (_rc_scan_locked
491  || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
492 
493  if (newBytes > 0) {
494  // parse new data
495  uint8_t st24_rssi, lost_count;
496 
497  rc_updated = false;
498 
499  for (unsigned i = 0; i < (unsigned)newBytes; i++) {
500  /* set updated flag if one complete packet was parsed */
501  st24_rssi = RC_INPUT_RSSI_MAX;
502  rc_updated = (OK == st24_decode(_rcs_buf[i], &st24_rssi, &lost_count,
503  &_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
504  }
505 
506  // The st24 will keep outputting RC channels and RSSI even if RC has been lost.
507  // The only way to detect RC loss is therefore to look at the lost_count.
508 
509  if (rc_updated) {
510  if (lost_count == 0) {
511  // we have a new ST24 frame. Publish it.
512  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_ST24;
513  fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp,
514  false, false, frame_drops, st24_rssi);
515  _rc_scan_locked = true;
516 
517  } else {
518  // if the lost count > 0 means that there is an RC loss
519  _rc_in.rc_lost = true;
520  }
521  }
522  }
523 
524  } else {
525  // Scan the next protocol
527  }
528 
529  break;
530 
531  case RC_SCAN_SUMD:
532  if (_rc_scan_begin == 0) {
533  _rc_scan_begin = cycle_timestamp;
534  // Configure serial port for DSM
536  rc_io_invert(false);
537 
538  } else if (_rc_scan_locked
539  || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
540 
541  if (newBytes > 0) {
542  // parse new data
543  uint8_t sumd_rssi, rx_count;
544  bool sumd_failsafe;
545 
546  rc_updated = false;
547 
548  for (unsigned i = 0; i < (unsigned)newBytes; i++) {
549  /* set updated flag if one complete packet was parsed */
550  sumd_rssi = RC_INPUT_RSSI_MAX;
551  rc_updated = (OK == sumd_decode(_rcs_buf[i], &sumd_rssi, &rx_count,
552  &_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS, &sumd_failsafe));
553  }
554 
555  if (rc_updated) {
556  // we have a new SUMD frame. Publish it.
557  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_SUMD;
558  fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp,
559  false, sumd_failsafe, frame_drops, sumd_rssi);
560  _rc_scan_locked = true;
561  }
562  }
563 
564  } else {
565  // Scan the next protocol
567  }
568 
569  break;
570 
571  case RC_SCAN_PPM:
572  // skip PPM if it's not supported
573 #ifdef HRT_PPM_CHANNEL
574  if (_rc_scan_begin == 0) {
575  _rc_scan_begin = cycle_timestamp;
576  // Configure timer input pin for CPPM
577  px4_arch_configgpio(GPIO_PPM_IN);
578  rc_io_invert(false);
579  ioctl(_rcs_fd, TIOCSINVERT, 0);
580 
581  } else if (_rc_scan_locked || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
582 
583  // see if we have new PPM input data
585  // we have a new PPM frame. Publish it.
586  rc_updated = true;
587  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM;
588  fill_rc_in(ppm_decoded_channels, ppm_buffer, cycle_timestamp, false, false, 0);
589  _rc_scan_locked = true;
592  }
593 
594  } else {
595  // disable CPPM input by mapping it away from the timer capture input
596  px4_arch_unconfiggpio(GPIO_PPM_IN);
597  // Scan the next protocol
599  }
600 
601 #else // skip PPM if it's not supported
603 
604 #endif // HRT_PPM_CHANNEL
605 
606  break;
607 
608  case RC_SCAN_CRSF:
609  if (_rc_scan_begin == 0) {
610  _rc_scan_begin = cycle_timestamp;
611  // Configure serial port for CRSF
613  rc_io_invert(false);
614 
615  } else if (_rc_scan_locked
616  || cycle_timestamp - _rc_scan_begin < rc_scan_max) {
617 
618  // parse new data
619  if (newBytes > 0) {
620  rc_updated = crsf_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
621  input_rc_s::RC_INPUT_MAX_CHANNELS);
622 
623  if (rc_updated) {
624  // we have a new CRSF frame. Publish it.
625  _rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_CRSF;
626  fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0);
627 
628  // Enable CRSF Telemetry only on the Omnibus, because on Pixhawk (-related) boards
629  // we cannot write to the RC UART
630  // It might work on FMU-v5. Or another option is to use a different UART port
631 #ifdef CONFIG_ARCH_BOARD_OMNIBUS_F4SD
632 
633  if (!_rc_scan_locked && !_crsf_telemetry) {
635  }
636 
637 #endif /* CONFIG_ARCH_BOARD_OMNIBUS_F4SD */
638 
639  _rc_scan_locked = true;
640 
641  if (_crsf_telemetry) {
642  _crsf_telemetry->update(cycle_timestamp);
643  }
644  }
645  }
646 
647  } else {
648  // Scan the next protocol
650  }
651 
652  break;
653  }
654 
655 #else // RC_SERIAL_PORT not defined
656 #ifdef HRT_PPM_CHANNEL
657 
658  // see if we have new PPM input data
660  // we have a new PPM frame. Publish it.
661  rc_updated = true;
662  fill_rc_in(ppm_decoded_channels, ppm_buffer, cycle_timestamp, false, false, 0);
665  }
666 
667 #endif // HRT_PPM_CHANNEL
668 #endif // RC_SERIAL_PORT
669 
671 
672  if (rc_updated) {
674 
676 
677  } else if (!rc_updated && ((hrt_absolute_time() - _rc_in.timestamp_last_signal) > 1_s)) {
678  _rc_scan_locked = false;
679  }
680 
681  if (_run_as_task) {
682  if (should_exit()) {
683  break;
684  }
685 
686  } else {
687  if (should_exit()) {
688  exit_and_cleanup();
689 
690  } else {
691  /* schedule next cycle */
692  work_queue(HPWORK, &_work, (worker_t)&RCInput::cycle_trampoline, this, USEC2TICK(_current_update_interval));
693  }
694 
695  break;
696  }
697  }
698 }
699 
700 #if defined(SPEKTRUM_POWER)
701 bool bind_spektrum(int arg)
702 {
703  int ret = PX4_ERROR;
704 
705  /* specify 11ms DSMX. RX will automatically fall back to 22ms or DSM2 if necessary */
706 
707  /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
708  PX4_INFO("DSM_BIND_START: DSM%s RX", (arg == 0) ? "2" : ((arg == 1) ? "-X" : "-X8"));
709 
710  if (arg == DSM2_BIND_PULSES ||
711  arg == DSMX_BIND_PULSES ||
712  arg == DSMX8_BIND_PULSES) {
713 
714  dsm_bind(DSM_CMD_BIND_POWER_DOWN, 0);
715 
716  dsm_bind(DSM_CMD_BIND_SET_RX_OUT, 0);
717  usleep(500000);
718 
719  dsm_bind(DSM_CMD_BIND_POWER_UP, 0);
720  usleep(72000);
721 
722  irqstate_t flags = px4_enter_critical_section();
723  dsm_bind(DSM_CMD_BIND_SEND_PULSES, arg);
724  px4_leave_critical_section(flags);
725 
726  usleep(50000);
727 
728  dsm_bind(DSM_CMD_BIND_REINIT_UART, 0);
729 
730  ret = OK;
731 
732  } else {
733  PX4_ERR("DSM bind failed");
734  ret = -EINVAL;
735  }
736 
737  return (ret == PX4_OK);
738 }
739 #endif /* SPEKTRUM_POWER */
740 
741 RCInput *RCInput::instantiate(int argc, char *argv[])
742 {
743  // No arguments to parse. We also know that we should run as task
744  return new RCInput(true, argv[0]);
745 }
746 
747 int RCInput::custom_command(int argc, char *argv[])
748 {
749 #if defined(SPEKTRUM_POWER)
750  const char *verb = argv[0];
751 
752  if (!strcmp(verb, "bind")) {
753  bind_spektrum(DSMX8_BIND_PULSES);
754  return 0;
755  }
756 
757 #endif /* SPEKTRUM_POWER */
758 
759  /* start the FMU if not running */
760  if (!is_running()) {
761  int ret = RCInput::task_spawn(argc, argv);
762 
763  if (ret) {
764  return ret;
765  }
766  }
767 
768  return print_usage("unknown command");
769 }
770 
772 {
773  PX4_INFO("Running %s", (_run_as_task ? "as task" : "on work queue"));
774 
775  if (!_run_as_task) {
776  PX4_INFO("Max update rate: %i Hz", 1000000 / _current_update_interval);
777  }
778 
779  if (_device[0] != '\0') {
780  PX4_INFO("Serial device: %s", _device);
781  }
782 
783  PX4_INFO("RC scan state: %s, locked: %s", RC_SCAN_STRING[_rc_scan_state], _rc_scan_locked ? "yes" : "no");
784  PX4_INFO("CRSF Telemetry: %s", _crsf_telemetry ? "yes" : "no");
785  PX4_INFO("SBUS frame drops: %u", sbus_dropped_frames());
786 
787 #if ADC_RC_RSSI_CHANNEL
788  PX4_INFO("vrssi: %dmV", (int)(_analog_rc_rssi_volt * 1000.0f));
789 #endif
790 
793 
794  if (hrt_elapsed_time(&_rc_in.timestamp) < 1_s) {
795  print_message(_rc_in);
796  }
797 
798  return 0;
799 }
800 
801 int
802 RCInput::print_usage(const char *reason)
803 {
804  if (reason) {
805  PX4_WARN("%s\n", reason);
806  }
807 
808  PRINT_MODULE_DESCRIPTION(
809  R"DESCR_STR(
810 ### Description
811 This module does the RC input parsing and auto-selecting the method. Supported methods are:
812 - PPM
813 - SBUS
814 - DSM
815 - SUMD
816 - ST24
817 - TBS Crossfire (CRSF)
818 
819 ### Implementation
820 By default the module runs on the work queue, to reduce RAM usage. It can also be run in its own thread,
821 specified via start flag -t, to reduce latency.
822 When running on the work queue, it schedules at a fixed frequency.
823 )DESCR_STR");
824 
825  PRINT_MODULE_USAGE_NAME("rc_input", "driver");
826  PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start the task (without any mode set, use any of the mode_* cmds)");
827  PRINT_MODULE_USAGE_PARAM_FLAG('t', "Run as separate task instead of the work queue", true);
828  PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS3", "<file:dev>", "RC device", true);
829 
830 #if defined(SPEKTRUM_POWER)
831  PRINT_MODULE_USAGE_COMMAND_DESCR("bind", "Send a DSM bind command (module must be running)");
832 #endif /* SPEKTRUM_POWER */
833 
834  PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
835 
836  return 0;
837 }
838 
839 extern "C" __EXPORT int rc_input_main(int argc, char *argv[])
840 {
841  return RCInput::main(argc, argv);
842 }
static RCInput * instantiate(int argc, char *argv[])
Definition: RCInput.cpp:741
__EXPORT int rc_input_main(int argc, char *argv[])
Definition: RCInput.cpp:839
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, bool *failsafe)
Decoder for SUMD/SUMH protocol.
Definition: sumd.cpp:111
bool _report_lock
Definition: RCInput.hpp:118
uint16_t _raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS]
Definition: RCInput.hpp:141
CRSFTelemetry * _crsf_telemetry
Definition: RCInput.hpp:144
int32_t rssi
Definition: input_rc.h:72
hrt_abstime _rc_scan_begin
Definition: RCInput.hpp:115
float channel_value[12]
Definition: adc_report.h:54
measure the time elapsed performing an event
Definition: perf_counter.h:56
__EXPORT uint16_t ppm_frame_length
length of the decoded PPM frame (includes gap)
bool rc_failsafe
Definition: input_rc.h:77
int main(int argc, char **argv)
Definition: main.cpp:3
uint16_t rc_ppm_frame_length
Definition: input_rc.h:75
static void cycle_trampoline(void *arg)
Definition: RCInput.cpp:215
Definition: I2C.hpp:51
virtual ~RCInput()
Definition: RCInput.cpp:72
uint8_t input_source
Definition: input_rc.h:79
void fill_rc_in(uint16_t raw_rc_count_local, uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS], hrt_abstime now, bool frame_drop, bool failsafe, unsigned frame_drops, int rssi)
Definition: RCInput.cpp:222
void rc_io_invert(bool invert)
bool crsf_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values, uint16_t *num_values, uint16_t max_channels)
Parse the CRSF protocol and extract RC channel data.
Definition: crsf.cpp:166
uint64_t timestamp
Definition: input_rc.h:69
static bool is_running()
Definition: dataman.cpp:415
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
bool _rc_scan_locked
Definition: RCInput.hpp:117
uint16_t rc_lost_frame_count
Definition: input_rc.h:73
void dsm_deinit()
Definition: dsm.cpp:313
enum RCInput::RC_SCAN RC_SCAN_SBUS
static int custom_command(int argc, char *argv[])
Definition: RCInput.cpp:747
uORB::Subscription _adc_sub
Definition: RCInput.hpp:127
static void cycle_trampoline_init(void *arg)
Definition: RCInput.cpp:193
int _rcs_fd
Definition: RCInput.hpp:136
unsigned sbus_dropped_frames()
The number of incomplete frames we encountered.
Definition: sbus.cpp:128
static void read(bootloader_app_shared_t *pshared)
int crsf_config(int uart_fd)
Configure an UART port to be used for CRSF.
Definition: crsf.cpp:147
__EXPORT hrt_abstime ppm_last_valid_decode
timestamp of the last valid decode
void perf_count(perf_counter_t handle)
Count a performance event.
void run() override
Definition: RCInput.cpp:305
unsigned _current_update_interval
Definition: RCInput.hpp:120
void perf_free(perf_counter_t handle)
Free a counter.
bool update(const hrt_abstime &now)
Send telemetry data.
static struct work_s _work
Definition: RCInput.hpp:124
uint16_t values[18]
Definition: input_rc.h:76
float _analog_rc_rssi_volt
Definition: RCInput.hpp:131
#define DSMX8_BIND_PULSES
Definition: dsm.h:92
#define perf_alloc(a, b)
Definition: px4io.h:59
RCInput(bool run_as_task, char *device)
Definition: RCInput.cpp:47
uint32_t channel_count
Definition: input_rc.h:71
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
High-level class that handles sending of CRSF telemetry data.
static constexpr char const * RC_SCAN_STRING[6]
Definition: RCInput.hpp:106
void perf_end(perf_counter_t handle)
End a performance event.
bool _analog_rc_rssi_stable
Definition: RCInput.hpp:132
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: dsm.cpp:640
uORB::Subscription _vehicle_cmd_sub
Definition: RCInput.hpp:126
#define SBUS_BUFFER_SIZE
Definition: sbus.h:50
static int task_spawn(int argc, char *argv[])
Definition: RCInput.cpp:121
uORB::PublicationMulti< input_rc_s > _to_input_rc
Definition: RCInput.hpp:134
perf_counter_t _publish_interval_perf
Definition: RCInput.hpp:147
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define DSM2_BIND_PULSES
Definition: dsm.h:90
int16_t channel_id[12]
Definition: adc_report.h:55
#define RC_INPUT_RSSI_MAX
Maximum RSSI value.
Definition: drv_rc_input.h:64
__EXPORT unsigned ppm_decoded_channels
count of decoded channels
int dsm_init(const char *device)
Initialize the DSM receive functionality.
Definition: dsm.cpp:293
#define DSMX_BIND_PULSES
Definition: dsm.h:91
uint16_t rc_total_frame_count
Definition: input_rc.h:74
int init()
Definition: RCInput.cpp:87
bool rc_lost
Definition: input_rc.h:78
uint16_t _raw_rc_count
Definition: RCInput.hpp:142
uint8_t _rcs_buf[SBUS_BUFFER_SIZE]
Definition: RCInput.hpp:139
int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Decoder for ST24 protocol.
Definition: st24.cpp:98
char _device[20]
device / serial port path
Definition: RCInput.hpp:137
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
__BEGIN_DECLS __EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS]
decoded PPM channel values
int print_status() override
Definition: RCInput.cpp:771
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: sbus.cpp:343
#define OK
Definition: uavcan_main.cpp:71
int dsm_config(int fd)
Definition: dsm.cpp:240
bool update(void *dst)
Update the struct.
void set_rc_scan_state(RC_SCAN _rc_scan_state)
bool _run_as_task
Definition: RCInput.hpp:122
input_rc_s _rc_in
Definition: RCInput.hpp:129
bool publish(const T &data)
Publish the struct.
void cycle()
run the main loop: if running as task, continuously iterate, otherwise execute only one single cycle ...
Definition: RCInput.cpp:319
perf_counter_t _cycle_perf
Definition: RCInput.hpp:146
static int print_usage(const char *reason=nullptr)
Definition: RCInput.cpp:802
queue struct.
void perf_begin(perf_counter_t handle)
Begin a performance event.
uint64_t timestamp_last_signal
Definition: input_rc.h:70
measure the interval between instances of an event
Definition: perf_counter.h:57
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
int sbus_config(int sbus_fd, bool singlewire)
Parse serial bytes on the S.BUS bus.
Definition: sbus.cpp:153