APM:Libraries
UART_test.cpp
Go to the documentation of this file.
1 /*
2  simple test of UART interfaces
3  */
4 
5 #include <AP_HAL/AP_HAL.h>
6 
7 #if HAL_OS_POSIX_IO
8 #include <stdio.h>
9 #endif
10 
11 void setup();
12 void loop();
13 
15 
16 /*
17  setup one UART at 57600
18  */
19 static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
20 {
21  if (uart == nullptr) {
22  // that UART doesn't exist on this platform
23  return;
24  }
25  uart->begin(57600);
26 }
27 
28 
29 void setup(void)
30 {
31  /*
32  start all UARTs at 57600 with default buffer sizes
33  */
34 
35  hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
36 
37  setup_uart(hal.uartA, "uartA"); // console
38  setup_uart(hal.uartB, "uartB"); // 1st GPS
39  setup_uart(hal.uartC, "uartC"); // telemetry 1
40  setup_uart(hal.uartD, "uartD"); // telemetry 2
41  setup_uart(hal.uartE, "uartE"); // 2nd GPS
42 }
43 
44 static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
45 {
46  if (uart == nullptr) {
47  // that UART doesn't exist on this platform
48  return;
49  }
50  uart->printf("Hello on UART %s at %.3f seconds\n",
51  name, (double)(AP_HAL::millis() * 0.001f));
52 }
53 
54 void loop(void)
55 {
56  test_uart(hal.uartA, "uartA");
57  test_uart(hal.uartB, "uartB");
58  test_uart(hal.uartC, "uartC");
59  test_uart(hal.uartD, "uartD");
60  test_uart(hal.uartE, "uartE");
61 
62  // also do a raw printf() on some platforms, which prints to the
63  // debug console
64 #if HAL_OS_POSIX_IO
65  ::printf("Hello on debug console at %.3f seconds\n", (double)(AP_HAL::millis() * 0.001f));
66 #endif
67 
68  hal.scheduler->delay(1000);
69 }
70 
71 AP_HAL_MAIN();
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
void loop()
Definition: UART_test.cpp:54
virtual void begin(uint32_t baud)=0
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
const char * name
Definition: BusTest.cpp:11
void setup()
Definition: UART_test.cpp:29
virtual void delay(uint16_t ms)=0
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define f(i)
uint32_t millis()
Definition: system.cpp:157
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
Definition: UART_test.cpp:44
AP_HAL_MAIN()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: UART_test.cpp:14
const HAL & get_HAL()
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
Definition: UART_test.cpp:19
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114