mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL: examples: fix coding style
This commit is contained in:
parent
c82f28f35a
commit
9ac63d7128
@ -53,27 +53,27 @@ static void test_printf(void)
|
|||||||
for (i=0; i < ARRAY_SIZE(float_tests); i++) {
|
for (i=0; i < ARRAY_SIZE(float_tests); i++) {
|
||||||
int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, float_tests[i].v);
|
int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, float_tests[i].v);
|
||||||
if (strcmp(buf, float_tests[i].result) != 0) {
|
if (strcmp(buf, float_tests[i].result) != 0) {
|
||||||
hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
|
hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
|
||||||
(unsigned)i,
|
(unsigned)i,
|
||||||
float_tests[i].fmt,
|
float_tests[i].fmt,
|
||||||
buf,
|
buf,
|
||||||
float_tests[i].result);
|
float_tests[i].result);
|
||||||
failures++;
|
failures++;
|
||||||
}
|
}
|
||||||
if (ret != strlen(float_tests[i].result)) {
|
if (ret != strlen(float_tests[i].result)) {
|
||||||
hal.console->printf("Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
|
hal.console->printf("Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
|
||||||
(unsigned)i,
|
(unsigned)i,
|
||||||
ret, (int)strlen(float_tests[i].result),
|
ret, (int)strlen(float_tests[i].result),
|
||||||
float_tests[i].fmt,
|
float_tests[i].fmt,
|
||||||
float_tests[i].result);
|
float_tests[i].result);
|
||||||
failures++;
|
failures++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.console->printf("%u failures\n", (unsigned)failures);
|
hal.console->printf("%u failures\n", (unsigned)failures);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void)
|
void loop(void)
|
||||||
{
|
{
|
||||||
test_printf();
|
test_printf();
|
||||||
hal.scheduler->delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user