RCInput.cpp 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. /*
  2. simple test of RC input interface
  3. */
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. // we need a boardconfig created so that the io processor's enable
  7. // parameter is available
  8. #if HAL_WITH_IO_MCU
  9. #include <AP_BoardConfig/AP_BoardConfig.h>
  10. #include <AP_IOMCU/AP_IOMCU.h>
  11. AP_BoardConfig BoardConfig;
  12. #endif
  13. void setup();
  14. void loop();
  15. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  16. #define MAX_CHANNELS 16
  17. static uint8_t max_channels_display = 8; // Set to 0 for display numbers of channels detected.
  18. static uint16_t last_value[MAX_CHANNELS];
  19. void setup(void)
  20. {
  21. hal.console->printf("Starting RCInput test\n");
  22. #if HAL_WITH_IO_MCU
  23. BoardConfig.init();
  24. #endif
  25. }
  26. void read_channels(void);
  27. void read_channels(void)
  28. {
  29. uint8_t nchannels = hal.rcin->num_channels(); // Get the numbers channels detected by RC_INPUT.
  30. if (nchannels == 0) {
  31. hal.console->printf("No channels detected\n");
  32. return;
  33. }
  34. if (max_channels_display == 0) {
  35. hal.console->printf("Channels detected: %2u\n", nchannels);
  36. hal.console->printf("Set max_channels_display > 0 to display channels values\n");
  37. return;
  38. }
  39. if (nchannels > MAX_CHANNELS) {
  40. nchannels = MAX_CHANNELS;
  41. }
  42. bool changed = false;
  43. for (uint8_t i = 0; i < nchannels; i++) {
  44. uint16_t v = hal.rcin->read(i);
  45. if (last_value[i] != v) {
  46. changed = true;
  47. last_value[i] = v;
  48. }
  49. }
  50. if (max_channels_display > nchannels) {
  51. max_channels_display = nchannels;
  52. }
  53. if (changed) {
  54. for (uint8_t i = 0; i < max_channels_display; i++) {
  55. hal.console->printf("%2u:%04u ", (unsigned)i+1, (unsigned)last_value[i]);
  56. }
  57. hal.console->printf("\n");
  58. }
  59. }
  60. void loop(void) {
  61. read_channels();
  62. hal.scheduler->delay(100);
  63. }
  64. AP_HAL_MAIN();