test_vsnprintf.cpp 2.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162
  1. #include <AP_gtest.h>
  2. #include <AP_HAL/HAL.h>
  3. #include <AP_HAL/Util.h>
  4. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  5. #define streq(x, y) (!strcmp(x, y))
  6. // from the GNU snprintf manpage:
  7. // The functions snprintf() and vsnprintf() do not write more than size
  8. // bytes (including the terminating null byte ('\0')). If the output was
  9. // truncated due to this limit, then the return value is the number of
  10. // characters (excluding the terminating null byte) which would have been
  11. // written to the final string if enough space had been available. Thus,
  12. // a return value of size or more means that the output was truncated.
  13. TEST(vsnprintf_Test, Basic)
  14. {
  15. char output[300];
  16. {
  17. int bytes_required = hal.util->snprintf(output, ARRAY_SIZE(output), "Fred: %u", 37);
  18. EXPECT_TRUE(streq(output, "Fred: 37"));
  19. EXPECT_EQ(bytes_required, 8);
  20. }
  21. {
  22. int bytes_required = hal.util->snprintf(output, 3, "Fred: %u", 37);
  23. EXPECT_TRUE(streq(output, "Fr"));
  24. EXPECT_EQ(bytes_required, 8);
  25. }
  26. {
  27. snprintf(output, ARRAY_SIZE(output), "0123");
  28. int bytes_required = hal.util->snprintf(output, 0, "Fred: %u", 37);
  29. EXPECT_TRUE(streq(output, "0123"));
  30. EXPECT_EQ(bytes_required, 8);
  31. }
  32. { // ensure rest of buffer survives
  33. memset(output, 'A', 10);
  34. const int bytes_required = snprintf(output, 5, "012345678");
  35. EXPECT_TRUE(streq(output, "0123"));
  36. EXPECT_EQ(bytes_required, 9);
  37. EXPECT_EQ(output[6], 'A');
  38. }
  39. { // simple float
  40. const int bytes_required = hal.util->snprintf(output, ARRAY_SIZE(output), "%f", 1/3.0);
  41. EXPECT_EQ(bytes_required, 8);
  42. EXPECT_TRUE(streq(output, "0.333333"));
  43. }
  44. { // less simple float
  45. const int bytes_required = hal.util->snprintf(output, ARRAY_SIZE(output), "%30.9f", 1/3.0);
  46. EXPECT_EQ(bytes_required, 28);
  47. EXPECT_TRUE(streq(output, " 0.3333333"));
  48. }
  49. { // simple string
  50. const int bytes_required = hal.util->snprintf(output, ARRAY_SIZE(output), "%s %s %c", "ABC", "DEF", 'x');
  51. EXPECT_EQ(bytes_required, 9);
  52. EXPECT_TRUE(streq(output, "ABC DEF x"));
  53. }
  54. }
  55. AP_GTEST_MAIN()