UART_test.cpp 1.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. /*
  2. simple test of UART interfaces
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. #if HAL_OS_POSIX_IO
  6. #include <stdio.h>
  7. #endif
  8. void setup();
  9. void loop();
  10. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  11. /*
  12. setup one UART at 57600
  13. */
  14. static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
  15. {
  16. if (uart == nullptr) {
  17. // that UART doesn't exist on this platform
  18. return;
  19. }
  20. uart->begin(57600);
  21. }
  22. void setup(void)
  23. {
  24. /*
  25. start all UARTs at 57600 with default buffer sizes
  26. */
  27. hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
  28. setup_uart(hal.uartA, "uartA"); // console
  29. setup_uart(hal.uartB, "uartB"); // 1st GPS
  30. setup_uart(hal.uartC, "uartC"); // telemetry 1
  31. setup_uart(hal.uartD, "uartD"); // telemetry 2
  32. setup_uart(hal.uartE, "uartE"); // 2nd GPS
  33. }
  34. static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
  35. {
  36. if (uart == nullptr) {
  37. // that UART doesn't exist on this platform
  38. return;
  39. }
  40. uart->printf("Hello on UART %s at %.3f seconds\n",
  41. name, (double)(AP_HAL::millis() * 0.001f));
  42. }
  43. void loop(void)
  44. {
  45. test_uart(hal.uartA, "uartA");
  46. test_uart(hal.uartB, "uartB");
  47. test_uart(hal.uartC, "uartC");
  48. test_uart(hal.uartD, "uartD");
  49. test_uart(hal.uartE, "uartE");
  50. // also do a raw printf() on some platforms, which prints to the
  51. // debug console
  52. #if HAL_OS_POSIX_IO
  53. ::printf("Hello on debug console at %.3f seconds\n", (double)(AP_HAL::millis() * 0.001f));
  54. #endif
  55. hal.scheduler->delay(1000);
  56. }
  57. AP_HAL_MAIN();