APM:Libraries
Util.cpp
Go to the documentation of this file.
1 #include "AP_HAL.h"
2 #include "Util.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 
13 /* Helper class implements AP_HAL::Print so we can use utility/vprintf */
15 public:
16  BufferPrinter(char* str, size_t size) : _offs(0), _str(str), _size(size) {}
17 
18  size_t write(uint8_t c) override {
19  if (_offs < _size) {
20  _str[_offs] = c;
21  _offs++;
22  return 1;
23  } else {
24  return 0;
25  }
26  }
27  size_t write(const uint8_t *buffer, size_t size) override {
28  size_t n = 0;
29  while (size--) {
30  n += write(*buffer++);
31  }
32  return n;
33  }
34 
35  size_t _offs;
36  char* const _str;
37  const size_t _size;
38 
39  uint32_t available() override { return 0; }
40  int16_t read() override { return -1; }
41  uint32_t txspace() override { return 0; }
42 };
43 
44 int AP_HAL::Util::snprintf(char* str, size_t size, const char *format, ...)
45 {
46  va_list ap;
47  va_start(ap, format);
48  int res = vsnprintf(str, size, format, ap);
49  va_end(ap);
50  return res;
51 }
52 
53 int AP_HAL::Util::vsnprintf(char* str, size_t size, const char *format, va_list ap)
54 {
55  BufferPrinter buf(str, size);
56  print_vprintf(&buf, format, ap);
57  // null terminate if possible
58  int ret = buf._offs;
59  buf.write(0);
60  return ret;
61 }
62 
64 {
65 #if defined(__APPLE__) && defined(__MACH__)
66  struct timeval ts;
67  gettimeofday(&ts, nullptr);
68  return ((long long)((ts.tv_sec * 1000) + (ts.tv_usec / 1000)));
69 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
70  return ST2MS(chVTGetSystemTime());
71 #else
72  struct timespec ts;
73  clock_gettime(CLOCK_REALTIME, &ts);
74  const uint64_t seconds = ts.tv_sec;
75  const uint64_t nanoseconds = ts.tv_nsec;
76  return (seconds * 1000ULL + nanoseconds/1000000ULL);
77 #endif
78 }
79 
80 void AP_HAL::Util::get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const
81 {
82  // get time of day in ms
83  uint64_t time_ms = get_system_clock_ms();
84 
85  // separate time into ms, sec, min, hour and days but all expressed in milliseconds
86  ms = time_ms % 1000;
87  uint32_t sec_ms = (time_ms % (60 * 1000)) - ms;
88  uint32_t min_ms = (time_ms % (60 * 60 * 1000)) - sec_ms - ms;
89  uint32_t hour_ms = (time_ms % (24 * 60 * 60 * 1000)) - min_ms - sec_ms - ms;
90 
91  // convert times as milliseconds into appropriate units
92  sec = sec_ms / 1000;
93  min = min_ms / (60 * 1000);
94  hour = hour_ms / (60 * 60 * 1000);
95 }
96 
97 // get milliseconds from now to a target time of day expressed as hour, min, sec, ms
98 // match starts from first value that is not -1. I.e. specifying hour=-1, minutes=10 will ignore the hour and return time until 10 minutes past 12am (utc)
99 uint32_t AP_HAL::Util::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
100 {
101  // determine highest value specified (0=none, 1=ms, 2=sec, 3=min, 4=hour)
102  int8_t largest_element = 0;
103  if (hour != -1) {
104  largest_element = 4;
105  } else if (min != -1) {
106  largest_element = 3;
107  } else if (sec != -1) {
108  largest_element = 2;
109  } else if (ms != -1) {
110  largest_element = 1;
111  } else {
112  // exit immediately if no time specified
113  return 0;
114  }
115 
116  // get start_time_ms as h, m, s, ms
117  int32_t curr_hour, curr_min, curr_sec, curr_ms;
118  get_system_clock_utc(curr_hour, curr_min, curr_sec, curr_ms);
119  int32_t total_delay_ms = 0;
120 
121  // calculate ms to target
122  if (largest_element >= 1) {
123  total_delay_ms += ms - curr_ms;
124  }
125  if (largest_element == 1 && total_delay_ms < 0) {
126  return static_cast<uint32_t>(total_delay_ms += 1000);
127  }
128 
129  // calculate sec to target
130  if (largest_element >= 2) {
131  total_delay_ms += (sec - curr_sec)*1000;
132  }
133  if (largest_element == 2 && total_delay_ms < 0) {
134  return static_cast<uint32_t>(total_delay_ms += (60*1000));
135  }
136 
137  // calculate min to target
138  if (largest_element >= 3) {
139  total_delay_ms += (min - curr_min)*60*1000;
140  }
141  if (largest_element == 3 && total_delay_ms < 0) {
142  return static_cast<uint32_t>(total_delay_ms += (60*60*1000));
143  }
144 
145  // calculate hours to target
146  if (largest_element >= 4) {
147  total_delay_ms += (hour - curr_hour)*60*60*1000;
148  }
149  if (largest_element == 4 && total_delay_ms < 0) {
150  return static_cast<uint32_t>(total_delay_ms += (24*60*60*1000));
151  }
152 
153  // total delay in milliseconds
154  return static_cast<uint32_t>(total_delay_ms);
155 }
uint32_t txspace() override
Definition: Util.cpp:41
BufferPrinter(char *str, size_t size)
Definition: Util.cpp:16
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
size_t write(const uint8_t *buffer, size_t size) override
Definition: Util.cpp:27
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
Definition: Util.cpp:99
int16_t read() override
Definition: Util.cpp:40
int vsnprintf(char *str, size_t size, const char *fmt, va_list ap)
Definition: stdio.c:34
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
void get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const
Definition: Util.cpp:80
uint32_t available() override
Definition: Util.cpp:39
char *const _str
Definition: Util.cpp:36
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
size_t _offs
Definition: Util.cpp:35
const size_t _size
Definition: Util.cpp:37
uint64_t get_system_clock_ms() const
Definition: Util.cpp:63
size_t write(uint8_t c) override
Definition: Util.cpp:18