RCInputToRCOutput.cpp 1.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  1. /*
  2. RC input pass trough to RC output
  3. Max RC channels 14
  4. Max update rate 10 Hz
  5. Attention: If your board has safety switch,
  6. don't forget to push it to enable the PWM output.
  7. */
  8. #include <AP_HAL/AP_HAL.h>
  9. // we need a boardconfig created so that the io processor's enable
  10. // parameter is available
  11. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  12. #include <AP_BoardConfig/AP_BoardConfig.h>
  13. #include <AP_IOMCU/AP_IOMCU.h>
  14. AP_BoardConfig BoardConfig;
  15. #endif
  16. void setup();
  17. void loop();
  18. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  19. #define MAX_CHANNELS 14
  20. static uint8_t max_channels = 0;
  21. static uint16_t last_value[MAX_CHANNELS];
  22. void setup(void)
  23. {
  24. hal.console->printf("Starting RCInputToRCOutput test\n");
  25. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  26. BoardConfig.init();
  27. #endif
  28. for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
  29. hal.rcout->enable_ch(i);
  30. }
  31. }
  32. void loop(void)
  33. {
  34. bool changed = false;
  35. uint8_t nchannels = hal.rcin->num_channels();
  36. if (nchannels > MAX_CHANNELS) {
  37. nchannels = MAX_CHANNELS;
  38. }
  39. for (uint8_t i = 0; i < nchannels; i++) {
  40. uint16_t v = hal.rcin->read(i);
  41. if (last_value[i] != v) {
  42. hal.rcout->write(i, v);
  43. changed = true;
  44. last_value[i] = v;
  45. }
  46. if (i > max_channels) {
  47. max_channels = i;
  48. }
  49. }
  50. if (changed) {
  51. for (uint8_t i = 0; i < max_channels; i++) {
  52. hal.console->printf("%2u:%04u ", (unsigned)(i + 1), (unsigned)last_value[i]);
  53. }
  54. hal.console->printf("\n");
  55. }
  56. hal.scheduler->delay(100);
  57. }
  58. AP_HAL_MAIN();