APM:Libraries
Printf.cpp
Go to the documentation of this file.
1 #include <AP_Common/AP_Common.h>
2 #include <AP_HAL/AP_HAL.h>
3 
4 void setup();
5 void loop();
6 
8 
9 void setup(void) {
10  hal.console->printf("Starting Printf test\n");
11 }
12 
13 static const struct {
14  const char *fmt;
15  float v;
16  const char *result;
17 } float_tests[] = {
18  { "%f", 3.71f, "3.710000" },
19  { "%.1f", 3.71f, "3.7" },
20  { "%.1f", 3.75f, "3.8" },
21  { "%.2f", 3.75f, "3.75" },
22  { "%.7f", 3.75f, "3.750000" },
23  { "%f", 10.4f, "10.40000" },
24  { "%f", 10.6f, "10.60000" },
25  { "%f", 1020.4f, "1020.400" },
26  { "%f", 1030.6f, "1030.600" },
27  { "%f", 10.123456f, "10.12346" },
28  { "%f", 102.123456f, "102.1235" },
29  { "%f", 1020.123456f, "1020.123" },
30  { "%.6f", 10.123456f, "10.12346" },
31  { "%.6f", 102.123456f, "102.1235" },
32  { "%.6f", 1020.123456f, "1020.123" },
33  { "%f", 10304052.6f, "1.030405e+07" },
34  { "%f", 103040501.6f, "1.030405e+08" },
35  { "%f", 1030405023.6f, "1.030405e+09" },
36  { "%f", -1030.6f, "-1030.600" },
37  { "%f", -10304052.6f, "-1.030405e+07" },
38  { "%f", -103040501.6f, "-1.030405e+08" },
39  { "%f", -1030405023.6f, "-1.030405e+09" },
40  { "%e", 103040501.6f, "1.030405e+08" },
41  { "%g", 103040501.6f, "1.03041e+08" },
42  { "%e", -103040501.6f, "-1.030405e+08" },
43  { "%g", -103040501.6f, "-1.03041e+08" },
44  { "%.0f", 10.4f, "10" },
45  { "%.0f", 10.6f, "11" },
46  { "%.1f", 10.4f, "10.4" },
47  { "%.1f", 10.6f, "10.6" },
48 };
49 
50 static void test_printf(void)
51 {
52  uint8_t i;
53  char buf[30];
54  uint8_t failures = 0;
55  hal.console->printf("Running printf tests\n");
56  for (i=0; i < ARRAY_SIZE(float_tests); i++) {
57  int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, (double)float_tests[i].v);
58  if (strcmp(buf, float_tests[i].result) != 0) {
59  hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
60  (unsigned)i,
61  float_tests[i].fmt,
62  buf,
63  float_tests[i].result);
64  failures++;
65  }
66  if (ret != (int)strlen(float_tests[i].result)) {
67  hal.console->printf("Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
68  (unsigned)i,
69  ret, (int)strlen(float_tests[i].result),
70  float_tests[i].fmt,
71  float_tests[i].result);
72  failures++;
73  }
74  }
75  hal.console->printf("%u failures\n", (unsigned)failures);
76 }
77 
78 void loop(void)
79 {
80  test_printf();
81  hal.scheduler->delay(1000);
82 }
83 
84 AP_HAL_MAIN();
static const struct @39 float_tests[]
AP_HAL::UARTDriver * console
Definition: HAL.h:110
AP_HAL::Util * util
Definition: HAL.h:115
static void test_printf(void)
Definition: Printf.cpp:50
const char * result
Definition: Printf.cpp:16
virtual void delay(uint16_t ms)=0
AP_HAL_MAIN()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: Printf.cpp:7
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void loop()
Definition: Printf.cpp:78
const char * fmt
Definition: Printf.cpp:14
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const HAL & get_HAL()
Common definitions and utility routines for the ArduPilot libraries.
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
void setup()
Definition: Printf.cpp:9
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114