2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-10-20 09:34:10 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-05-28 04:21:56 -03:00
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2013-05-28 04:21:56 -03:00
|
|
|
|
|
|
|
void setup(void) {
|
2017-01-21 00:37:51 -04:00
|
|
|
hal.console->printf("Starting Printf test\n");
|
2013-05-28 04:21:56 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
static const struct {
|
|
|
|
const char *fmt;
|
|
|
|
float v;
|
|
|
|
const char *result;
|
|
|
|
} float_tests[] = {
|
|
|
|
{ "%f", 3.71f, "3.710000" },
|
|
|
|
{ "%.1f", 3.71f, "3.7" },
|
|
|
|
{ "%.1f", 3.75f, "3.8" },
|
|
|
|
{ "%.2f", 3.75f, "3.75" },
|
2013-09-21 00:29:52 -03:00
|
|
|
{ "%.7f", 3.75f, "3.750000" },
|
|
|
|
{ "%f", 10.4f, "10.40000" },
|
|
|
|
{ "%f", 10.6f, "10.60000" },
|
|
|
|
{ "%f", 1020.4f, "1020.400" },
|
|
|
|
{ "%f", 1030.6f, "1030.600" },
|
2013-09-21 02:45:05 -03:00
|
|
|
{ "%f", 10.123456f, "10.12346" },
|
|
|
|
{ "%f", 102.123456f, "102.1235" },
|
|
|
|
{ "%f", 1020.123456f, "1020.123" },
|
|
|
|
{ "%.6f", 10.123456f, "10.12346" },
|
|
|
|
{ "%.6f", 102.123456f, "102.1235" },
|
|
|
|
{ "%.6f", 1020.123456f, "1020.123" },
|
|
|
|
{ "%f", 10304052.6f, "1.030405e+07" },
|
|
|
|
{ "%f", 103040501.6f, "1.030405e+08" },
|
|
|
|
{ "%f", 1030405023.6f, "1.030405e+09" },
|
2013-09-21 00:29:52 -03:00
|
|
|
{ "%f", -1030.6f, "-1030.600" },
|
2013-09-21 02:45:05 -03:00
|
|
|
{ "%f", -10304052.6f, "-1.030405e+07" },
|
|
|
|
{ "%f", -103040501.6f, "-1.030405e+08" },
|
|
|
|
{ "%f", -1030405023.6f, "-1.030405e+09" },
|
|
|
|
{ "%e", 103040501.6f, "1.030405e+08" },
|
|
|
|
{ "%g", 103040501.6f, "1.03041e+08" },
|
|
|
|
{ "%e", -103040501.6f, "-1.030405e+08" },
|
|
|
|
{ "%g", -103040501.6f, "-1.03041e+08" },
|
2013-09-21 00:29:52 -03:00
|
|
|
{ "%.0f", 10.4f, "10" },
|
|
|
|
{ "%.0f", 10.6f, "11" },
|
|
|
|
{ "%.1f", 10.4f, "10.4" },
|
|
|
|
{ "%.1f", 10.6f, "10.6" },
|
2013-05-28 04:21:56 -03:00
|
|
|
};
|
|
|
|
|
2018-09-06 00:31:49 -03:00
|
|
|
static void test_printf_floats(void)
|
2013-05-28 04:21:56 -03:00
|
|
|
{
|
2018-09-06 00:31:49 -03:00
|
|
|
hal.console->printf("Starting Printf floats test\n");
|
|
|
|
|
2013-05-28 04:21:56 -03:00
|
|
|
uint8_t i;
|
|
|
|
char buf[30];
|
|
|
|
uint8_t failures = 0;
|
|
|
|
hal.console->printf("Running printf tests\n");
|
2015-07-20 16:53:47 -03:00
|
|
|
for (i=0; i < ARRAY_SIZE(float_tests); i++) {
|
2017-04-13 08:31:16 -03:00
|
|
|
int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, (double)float_tests[i].v);
|
2013-05-28 04:21:56 -03:00
|
|
|
if (strcmp(buf, float_tests[i].result) != 0) {
|
2016-05-03 22:21:03 -03:00
|
|
|
hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
|
|
|
|
(unsigned)i,
|
2013-05-28 04:21:56 -03:00
|
|
|
float_tests[i].fmt,
|
2013-09-21 00:29:52 -03:00
|
|
|
buf,
|
|
|
|
float_tests[i].result);
|
2013-05-28 04:21:56 -03:00
|
|
|
failures++;
|
|
|
|
}
|
2016-05-03 22:25:58 -03:00
|
|
|
if (ret != (int)strlen(float_tests[i].result)) {
|
2016-05-03 22:21:03 -03:00
|
|
|
hal.console->printf("Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
|
|
|
|
(unsigned)i,
|
2013-09-21 02:45:05 -03:00
|
|
|
ret, (int)strlen(float_tests[i].result),
|
|
|
|
float_tests[i].fmt,
|
|
|
|
float_tests[i].result);
|
2016-05-03 22:21:03 -03:00
|
|
|
failures++;
|
2013-09-21 02:45:05 -03:00
|
|
|
}
|
2013-05-28 04:21:56 -03:00
|
|
|
}
|
|
|
|
hal.console->printf("%u failures\n", (unsigned)failures);
|
|
|
|
}
|
|
|
|
|
2018-09-06 00:31:49 -03:00
|
|
|
static void test_printf_null_termination(void)
|
|
|
|
{
|
|
|
|
hal.console->printf("Starting Printf null-termination tests\n");
|
|
|
|
|
|
|
|
{
|
|
|
|
char buf[10];
|
|
|
|
int ret = hal.util->snprintf(buf,sizeof(buf), "%s", "ABCDEABCDE");
|
|
|
|
const int want = 9;
|
|
|
|
if (ret != want) {
|
|
|
|
hal.console->printf("snprintf returned %d expected %d\n", ret, want);
|
|
|
|
}
|
|
|
|
if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
|
|
|
|
hal.console->printf("Bad snprintf string (%s)\n", buf);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
{
|
|
|
|
char buf[10];
|
|
|
|
int ret = hal.util->snprintf(buf,sizeof(buf), "ABCDEABCDE");
|
|
|
|
const int want = 9;
|
|
|
|
if (ret != want) {
|
|
|
|
hal.console->printf("snprintf returned %d expected %d\n", ret, want);
|
|
|
|
}
|
|
|
|
if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
|
|
|
|
hal.console->printf("Bad snprintf string (%s)\n", buf);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
static void test_printf(void)
|
|
|
|
{
|
|
|
|
test_printf_floats();
|
|
|
|
test_printf_null_termination();
|
|
|
|
}
|
|
|
|
|
2016-05-03 22:21:03 -03:00
|
|
|
void loop(void)
|
|
|
|
{
|
2013-05-28 04:21:56 -03:00
|
|
|
test_printf();
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL_MAIN();
|