Util.cpp 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. #include "AP_HAL.h"
  2. #include "Util.h"
  3. #include "utility/print_vprintf.h"
  4. #if defined(__APPLE__) && defined(__MACH__)
  5. #include <sys/time.h>
  6. #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  7. #include "ch.h"
  8. #include "hal.h"
  9. #else
  10. #include <time.h>
  11. #endif
  12. /* Helper class implements AP_HAL::Print so we can use utility/vprintf */
  13. class BufferPrinter : public AP_HAL::BetterStream {
  14. public:
  15. BufferPrinter(char* str, size_t size) :
  16. _offs(0), _str(str), _size(size) {}
  17. size_t write(uint8_t c) override {
  18. if (_offs < _size) {
  19. _str[_offs] = c;
  20. }
  21. _offs++;
  22. return 1;
  23. }
  24. size_t write(const uint8_t *buffer, size_t size) override {
  25. size_t n = 0;
  26. while (size--) {
  27. n += write(*buffer++);
  28. }
  29. return n;
  30. }
  31. size_t _offs;
  32. char* const _str;
  33. const size_t _size;
  34. uint32_t available() override { return 0; }
  35. int16_t read() override { return -1; }
  36. uint32_t txspace() override { return 0; }
  37. };
  38. int AP_HAL::Util::snprintf(char* str, size_t size, const char *format, ...)
  39. {
  40. va_list ap;
  41. va_start(ap, format);
  42. int res = vsnprintf(str, size, format, ap);
  43. va_end(ap);
  44. return res;
  45. }
  46. int AP_HAL::Util::vsnprintf(char* str, size_t size, const char *format, va_list ap)
  47. {
  48. // note that size==0 must be handled as functions like vasprintf() rely on the return
  49. // value being the number of bytes that would be printed if there was enough space.
  50. BufferPrinter buf(str, size?size-1:0);
  51. print_vprintf(&buf, format, ap);
  52. // null terminate
  53. size_t ret = buf._offs;
  54. if (ret < size) {
  55. // if the string did fit then nul terminate
  56. str[ret] = '\0';
  57. } else if (size > 0) {
  58. // if it didn't fit then terminate using passed in size
  59. str[size-1] = 0;
  60. }
  61. return int(ret);
  62. }
  63. uint64_t AP_HAL::Util::get_hw_rtc() const
  64. {
  65. #if defined(__APPLE__) && defined(__MACH__)
  66. struct timeval ts;
  67. gettimeofday(&ts, nullptr);
  68. return ((long long)((ts.tv_sec * 1000000) + ts.tv_usec));
  69. #elif HAL_HAVE_GETTIME_SETTIME
  70. struct timespec ts;
  71. clock_gettime(CLOCK_REALTIME, &ts);
  72. const uint64_t seconds = ts.tv_sec;
  73. const uint64_t nanoseconds = ts.tv_nsec;
  74. return (seconds * 1000000ULL + nanoseconds/1000ULL);
  75. #endif
  76. // no HW clock (or not one worth bothering with)
  77. return 0;
  78. }
  79. void AP_HAL::Util::set_hw_rtc(uint64_t time_utc_usec)
  80. {
  81. #if HAL_HAVE_GETTIME_SETTIME
  82. timespec ts;
  83. ts.tv_sec = time_utc_usec/1000000ULL;
  84. ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000ULL;
  85. clock_settime(CLOCK_REALTIME, &ts);
  86. #endif
  87. }
  88. void AP_HAL::Util::set_soft_armed(const bool b)
  89. {
  90. if (b != soft_armed) {
  91. soft_armed = b;
  92. last_armed_change_ms = AP_HAL::millis();
  93. if (!was_watchdog_reset()) {
  94. persistent_data.armed = b;
  95. }
  96. }
  97. }