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" },
59 hal.
console->
printf(
"Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
67 hal.
console->
printf(
"Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
static const struct @39 float_tests[]
AP_HAL::UARTDriver * console
static void test_printf(void)
virtual void delay(uint16_t ms)=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void printf(const char *,...) FMT_PRINTF(2
Common definitions and utility routines for the ArduPilot libraries.
int snprintf(char *str, size_t size, const char *format,...)
AP_HAL::Scheduler * scheduler