Printf.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120
  1. #include <AP_Common/AP_Common.h>
  2. #include <AP_HAL/AP_HAL.h>
  3. void setup();
  4. void loop();
  5. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  6. void setup(void) {
  7. hal.console->printf("Starting Printf test\n");
  8. }
  9. static const struct {
  10. const char *fmt;
  11. float v;
  12. const char *result;
  13. } float_tests[] = {
  14. { "%f", 3.71f, "3.710000" },
  15. { "%.1f", 3.71f, "3.7" },
  16. { "%.1f", 3.75f, "3.8" },
  17. { "%.2f", 3.75f, "3.75" },
  18. { "%.7f", 3.75f, "3.750000" },
  19. { "%f", 10.4f, "10.40000" },
  20. { "%f", 10.6f, "10.60000" },
  21. { "%f", 1020.4f, "1020.400" },
  22. { "%f", 1030.6f, "1030.600" },
  23. { "%f", 10.123456f, "10.12346" },
  24. { "%f", 102.123456f, "102.1235" },
  25. { "%f", 1020.123456f, "1020.123" },
  26. { "%.6f", 10.123456f, "10.12346" },
  27. { "%.6f", 102.123456f, "102.1235" },
  28. { "%.6f", 1020.123456f, "1020.123" },
  29. { "%f", 10304052.6f, "1.030405e+07" },
  30. { "%f", 103040501.6f, "1.030405e+08" },
  31. { "%f", 1030405023.6f, "1.030405e+09" },
  32. { "%f", -1030.6f, "-1030.600" },
  33. { "%f", -10304052.6f, "-1.030405e+07" },
  34. { "%f", -103040501.6f, "-1.030405e+08" },
  35. { "%f", -1030405023.6f, "-1.030405e+09" },
  36. { "%e", 103040501.6f, "1.030405e+08" },
  37. { "%g", 103040501.6f, "1.03041e+08" },
  38. { "%e", -103040501.6f, "-1.030405e+08" },
  39. { "%g", -103040501.6f, "-1.03041e+08" },
  40. { "%.0f", 10.4f, "10" },
  41. { "%.0f", 10.6f, "11" },
  42. { "%.1f", 10.4f, "10.4" },
  43. { "%.1f", 10.6f, "10.6" },
  44. };
  45. static void test_printf_floats(void)
  46. {
  47. hal.console->printf("Starting Printf floats test\n");
  48. uint8_t i;
  49. char buf[30];
  50. uint8_t failures = 0;
  51. hal.console->printf("Running printf tests\n");
  52. for (i=0; i < ARRAY_SIZE(float_tests); i++) {
  53. int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, (double)float_tests[i].v);
  54. if (strcmp(buf, float_tests[i].result) != 0) {
  55. hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
  56. (unsigned)i,
  57. float_tests[i].fmt,
  58. buf,
  59. float_tests[i].result);
  60. failures++;
  61. }
  62. if (ret != (int)strlen(float_tests[i].result)) {
  63. hal.console->printf("Failed float_tests[%u] ret=%d/%d '%s' should be '%s'\n",
  64. (unsigned)i,
  65. ret, (int)strlen(float_tests[i].result),
  66. float_tests[i].fmt,
  67. float_tests[i].result);
  68. failures++;
  69. }
  70. }
  71. hal.console->printf("%u failures\n", (unsigned)failures);
  72. }
  73. static void test_printf_null_termination(void)
  74. {
  75. hal.console->printf("Starting Printf null-termination tests\n");
  76. {
  77. char buf[10];
  78. int ret = hal.util->snprintf(buf,sizeof(buf), "%s", "ABCDEABCDE");
  79. const int want = 9;
  80. if (ret != want) {
  81. hal.console->printf("snprintf returned %d expected %d\n", ret, want);
  82. }
  83. if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
  84. hal.console->printf("Bad snprintf string (%s)\n", buf);
  85. }
  86. }
  87. {
  88. char buf[10];
  89. int ret = hal.util->snprintf(buf,sizeof(buf), "ABCDEABCDE");
  90. const int want = 9;
  91. if (ret != want) {
  92. hal.console->printf("snprintf returned %d expected %d\n", ret, want);
  93. }
  94. if (!strncmp(buf, "ABCDEABCD", sizeof(buf))) {
  95. hal.console->printf("Bad snprintf string (%s)\n", buf);
  96. }
  97. }
  98. }
  99. static void test_printf(void)
  100. {
  101. test_printf_floats();
  102. test_printf_null_termination();
  103. }
  104. void loop(void)
  105. {
  106. test_printf();
  107. hal.scheduler->delay(1000);
  108. }
  109. AP_HAL_MAIN();