4 #if defined(__APPLE__) && defined(__MACH__) 6 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 18 size_t write(uint8_t c)
override {
30 n +=
write(*buffer++);
40 int16_t
read()
override {
return -1; }
48 int res =
vsnprintf(str, size, format, ap);
65 #if defined(__APPLE__) && defined(__MACH__) 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());
74 const uint64_t seconds = ts.tv_sec;
75 const uint64_t nanoseconds = ts.tv_nsec;
76 return (seconds * 1000ULL + nanoseconds/1000000ULL);
83 uint64_t time_ms = get_system_clock_ms();
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;
93 min = min_ms / (60 * 1000);
94 hour = hour_ms / (60 * 60 * 1000);
102 int8_t largest_element = 0;
105 }
else if (min != -1) {
107 }
else if (sec != -1) {
109 }
else if (ms != -1) {
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;
122 if (largest_element >= 1) {
123 total_delay_ms += ms - curr_ms;
125 if (largest_element == 1 && total_delay_ms < 0) {
126 return static_cast<uint32_t
>(total_delay_ms += 1000);
130 if (largest_element >= 2) {
131 total_delay_ms += (sec - curr_sec)*1000;
133 if (largest_element == 2 && total_delay_ms < 0) {
134 return static_cast<uint32_t
>(total_delay_ms += (60*1000));
138 if (largest_element >= 3) {
139 total_delay_ms += (min - curr_min)*60*1000;
141 if (largest_element == 3 && total_delay_ms < 0) {
142 return static_cast<uint32_t
>(total_delay_ms += (60*60*1000));
146 if (largest_element >= 4) {
147 total_delay_ms += (hour - curr_hour)*60*60*1000;
149 if (largest_element == 4 && total_delay_ms < 0) {
150 return static_cast<uint32_t
>(total_delay_ms += (24*60*60*1000));
154 return static_cast<uint32_t
>(total_delay_ms);
uint32_t txspace() override
BufferPrinter(char *str, size_t size)
void clock_gettime(uint32_t a1, void *a2)
static uint8_t buffer[SRXL_FRAMELEN_MAX]
size_t write(const uint8_t *buffer, size_t size) override
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
int vsnprintf(char *str, size_t size, const char *fmt, va_list ap)
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
void get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const
void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap)
uint32_t available() override
int snprintf(char *str, size_t size, const char *format,...)
uint64_t get_system_clock_ms() const
size_t write(uint8_t c) override