RCOutput.cpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. /*
  2. Simple test of RC output interface with Menu
  3. Attention: If your board has safety switch,
  4. don't forget to push it to enable the PWM output.
  5. */
  6. #include <AP_Common/AP_Common.h>
  7. #include <AP_HAL/AP_HAL.h>
  8. #include <AP_Menu/AP_Menu.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. void drive(uint16_t hz_speed);
  19. #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &Menu_Commands::func, int8_t, uint8_t, const Menu::arg *)
  20. #define ESC_HZ 490
  21. #define SERVO_HZ 50
  22. class Menu_Commands {
  23. public:
  24. /* Menu commands to drive a SERVO type with
  25. * repective PWM output freq defined by SERVO_HZ
  26. */
  27. int8_t menu_servo(uint8_t argc, const Menu::arg *argv);
  28. /* Menu commands to drive a ESC type with
  29. * repective PWM output freq defined by ESC_HZ
  30. */
  31. int8_t menu_esc(uint8_t argc, const Menu::arg *argv);
  32. };
  33. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  34. Menu_Commands commands;
  35. static uint16_t pwm = 1500;
  36. static int8_t delta = 1;
  37. /* Function to drive a RC output TYPE especified */
  38. void drive(uint16_t hz_speed) {
  39. hal.rcout->set_freq(0xFF, hz_speed);
  40. while (1) {
  41. for (uint8_t i = 0; i < 14; i++) {
  42. hal.rcout->write(i, pwm);
  43. pwm += delta;
  44. if (delta > 0 && pwm >= 2000) {
  45. delta = -1;
  46. hal.console->printf("reversing\n");
  47. } else if (delta < 0 && pwm <= 1000) {
  48. delta = 1;
  49. hal.console->printf("normalizing\n");
  50. }
  51. }
  52. hal.scheduler->delay(5);
  53. if (hal.console->available()) {
  54. break;
  55. }
  56. }
  57. }
  58. int8_t Menu_Commands::menu_servo(uint8_t argc, const Menu::arg *argv) {
  59. drive(SERVO_HZ);
  60. return 0;
  61. }
  62. int8_t Menu_Commands::menu_esc(uint8_t argc, const Menu::arg *argv) {
  63. drive(ESC_HZ);
  64. return 0;
  65. }
  66. const struct Menu::command rcoutput_menu_commands[] = {
  67. { "servo", MENU_FUNC(menu_servo) },
  68. { "esc", MENU_FUNC(menu_esc) },
  69. };
  70. MENU(menu, "Menu: ", rcoutput_menu_commands);
  71. void setup(void) {
  72. hal.console->printf("Starting AP_HAL::RCOutput test\n");
  73. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  74. BoardConfig.init();
  75. #endif
  76. for (uint8_t i = 0; i < 14; i++) {
  77. hal.rcout->enable_ch(i);
  78. }
  79. }
  80. void loop(void) {
  81. /* We call and run the menu, you can type help into menu to show commands
  82. * available */
  83. menu.run();
  84. }
  85. AP_HAL_MAIN();