RTC_Test.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  1. //
  2. // Simple test for the AP_RTC class
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_BoardConfig/AP_BoardConfig.h>
  6. #include <GCS_MAVLink/GCS_Dummy.h>
  7. #include <AP_Logger/AP_Logger.h>
  8. #include <stdio.h>
  9. void setup();
  10. void loop();
  11. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  12. static AP_BoardConfig board_config;
  13. static AP_SerialManager serial_manager;
  14. AP_Int32 logger_bitmask;
  15. static AP_Logger logger{logger_bitmask};
  16. static AP_RTC _rtc;
  17. void setup(void)
  18. {
  19. board_config.init();
  20. serial_manager.init();
  21. }
  22. void failed(const char *fmt_in, ...) FMT_PRINTF(1, 2);
  23. void failed(const char *fmt_in, ...)
  24. {
  25. va_list arg_list;
  26. char fmt[512];
  27. snprintf(fmt, ARRAY_SIZE(fmt), "### FAILED: %s\n\n", fmt_in);
  28. #pragma GCC diagnostic ignored "-Wvarargs"
  29. va_start(arg_list, fmt);
  30. hal.console->vprintf(fmt, arg_list);
  31. va_end(arg_list);
  32. hal.scheduler->delay(2000);
  33. }
  34. void loop(void)
  35. {
  36. static uint32_t last_run_ms;
  37. const uint32_t now_ms = AP_HAL::millis();
  38. if (now_ms - last_run_ms < 2345) {
  39. return;
  40. }
  41. last_run_ms = now_ms;
  42. uint32_t run_counter = 0;
  43. AP_RTC &rtc = AP::rtc();
  44. // kinda_now is a time around 11:30am in Australia
  45. uint64_t kinda_now = 1565918797000000;
  46. rtc.set_utc_usec(kinda_now, AP_RTC::SOURCE_GPS);
  47. hal.console->printf("%s: Test run %u\n", __FILE__, (unsigned)run_counter++);
  48. uint64_t now = 0;
  49. if (!rtc.get_utc_usec(now)) {
  50. failed("get_utc_usec failed");
  51. return;
  52. }
  53. hal.console->printf("Now=%llu\n", (long long unsigned)now);
  54. if (now < kinda_now) {
  55. failed("Universe time going backwards. Be afraid.");
  56. return;
  57. }
  58. { // generally make sure time is moving forward / initial time
  59. // offset looks right
  60. uint8_t hour, min, sec;
  61. uint16_t ms;
  62. if (!rtc.get_system_clock_utc(hour, min, sec, ms)) {
  63. failed("Failed to get hour/min/sec/ms");
  64. return;
  65. }
  66. if (run_counter == 0) {
  67. if (hour != 1 || min != 26) {
  68. failed("Unexpected hour/min");
  69. return;
  70. }
  71. }
  72. hal.console->printf("hour=%u min=%u sec=%u ms=%u\n", (unsigned)hour, (unsigned)min, (unsigned)sec, (unsigned)ms);
  73. uint32_t delta;
  74. // we make the assumption here that no more than a
  75. // millisecond can elapse between getting the system clock
  76. // above and these tests.
  77. delta = rtc.get_time_utc(hour, min, sec, ms + 1);
  78. if (delta != 1 && delta != 0) {
  79. failed("millisecond delta fail");
  80. }
  81. delta = rtc.get_time_utc(hour, min, sec + 1, ms);
  82. if (delta != 1000 && delta != 999) {
  83. failed("second delta fail");
  84. }
  85. delta = rtc.get_time_utc(hour, min + 1, sec, ms);
  86. if (delta != 60000 && delta != 59999) {
  87. failed("minute delta fail");
  88. }
  89. delta = rtc.get_time_utc(hour + 1, min, sec, ms);
  90. if (delta != 3600000 && delta != 3599999) {
  91. failed("hour delta fail");
  92. }
  93. if (min > 1) {
  94. delta = rtc.get_time_utc(hour, min-1, sec, ms);
  95. if (delta != 86340000 && delta != 86339999) {
  96. hal.console->printf("got: %u\n", (unsigned)rtc.get_time_utc(hour, min-1, sec, ms));
  97. failed("negative minute delta fail");
  98. }
  99. }
  100. }
  101. hal.console->printf("Test complete.\n\n");
  102. }
  103. const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  104. AP_GROUPEND
  105. };
  106. GCS_Dummy _gcs;
  107. AP_HAL_MAIN();