RCOutput.cpp 1.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152
  1. /*
  2. simple test of RC output interface
  3. Attention: If your board has safety switch,
  4. don't forget to push it to enable the PWM output.
  5. */
  6. #include <AP_HAL/AP_HAL.h>
  7. // we need a boardconfig created so that the io processor's enable
  8. // parameter is available
  9. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  10. #include <AP_BoardConfig/AP_BoardConfig.h>
  11. #include <AP_IOMCU/AP_IOMCU.h>
  12. AP_BoardConfig BoardConfig;
  13. #endif
  14. void setup();
  15. void loop();
  16. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  17. void setup (void)
  18. {
  19. hal.console->printf("Starting AP_HAL::RCOutput test\n");
  20. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  21. BoardConfig.init();
  22. #endif
  23. for (uint8_t i = 0; i< 14; i++) {
  24. hal.rcout->enable_ch(i);
  25. }
  26. }
  27. static uint16_t pwm = 1500;
  28. static int8_t delta = 1;
  29. void loop (void)
  30. {
  31. for (uint8_t i=0; i < 14; i++) {
  32. hal.rcout->write(i, pwm);
  33. pwm += delta;
  34. if (delta > 0 && pwm >= 2000) {
  35. delta = -1;
  36. hal.console->printf("decreasing\n");
  37. } else if (delta < 0 && pwm <= 1000) {
  38. delta = 1;
  39. hal.console->printf("increasing\n");
  40. }
  41. }
  42. hal.scheduler->delay(5);
  43. }
  44. AP_HAL_MAIN();