2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL.h"
|
2013-09-21 01:25:42 -03:00
|
|
|
#include "Util.h"
|
|
|
|
#include "utility/print_vprintf.h"
|
2016-06-21 07:50:01 -03:00
|
|
|
#if defined(__APPLE__) && defined(__MACH__)
|
|
|
|
#include <sys/time.h>
|
2018-01-05 03:07:23 -04:00
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
#include "ch.h"
|
|
|
|
#include "hal.h"
|
|
|
|
#else
|
|
|
|
#include <time.h>
|
2016-06-21 07:50:01 -03:00
|
|
|
#endif
|
2013-09-21 01:25:42 -03:00
|
|
|
|
|
|
|
/* Helper class implements AP_HAL::Print so we can use utility/vprintf */
|
2018-03-22 03:53:32 -03:00
|
|
|
class BufferPrinter : public AP_HAL::BetterStream {
|
2013-09-21 01:25:42 -03:00
|
|
|
public:
|
2019-09-10 22:36:35 -03:00
|
|
|
BufferPrinter(char* str, size_t size) :
|
|
|
|
_offs(0), _str(str), _size(size) {}
|
2018-03-22 03:53:32 -03:00
|
|
|
|
|
|
|
size_t write(uint8_t c) override {
|
2013-09-21 01:25:42 -03:00
|
|
|
if (_offs < _size) {
|
|
|
|
_str[_offs] = c;
|
|
|
|
}
|
2019-09-10 22:36:35 -03:00
|
|
|
_offs++;
|
|
|
|
return 1;
|
2013-09-21 01:25:42 -03:00
|
|
|
}
|
2018-03-22 03:53:32 -03:00
|
|
|
size_t write(const uint8_t *buffer, size_t size) override {
|
2013-10-02 04:36:01 -03:00
|
|
|
size_t n = 0;
|
|
|
|
while (size--) {
|
|
|
|
n += write(*buffer++);
|
|
|
|
}
|
|
|
|
return n;
|
|
|
|
}
|
|
|
|
|
2018-03-22 03:53:32 -03:00
|
|
|
size_t _offs;
|
2013-09-21 01:25:42 -03:00
|
|
|
char* const _str;
|
|
|
|
const size_t _size;
|
2018-03-22 03:53:32 -03:00
|
|
|
|
|
|
|
uint32_t available() override { return 0; }
|
|
|
|
int16_t read() override { return -1; }
|
|
|
|
uint32_t txspace() override { return 0; }
|
2013-09-21 01:25:42 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
int AP_HAL::Util::snprintf(char* str, size_t size, const char *format, ...)
|
|
|
|
{
|
|
|
|
va_list ap;
|
|
|
|
va_start(ap, format);
|
2013-09-21 02:45:05 -03:00
|
|
|
int res = vsnprintf(str, size, format, ap);
|
2013-09-21 01:25:42 -03:00
|
|
|
va_end(ap);
|
|
|
|
return res;
|
|
|
|
}
|
|
|
|
|
|
|
|
int AP_HAL::Util::vsnprintf(char* str, size_t size, const char *format, va_list ap)
|
|
|
|
{
|
2019-09-10 22:36:35 -03:00
|
|
|
// note that size==0 must be handled as functions like vasprintf() rely on the return
|
|
|
|
// value being the number of bytes that would be printed if there was enough space.
|
|
|
|
BufferPrinter buf(str, size?size-1:0);
|
2015-12-23 10:25:56 -04:00
|
|
|
print_vprintf(&buf, format, ap);
|
2018-08-26 22:18:10 -03:00
|
|
|
// null terminate
|
2019-09-10 22:36:35 -03:00
|
|
|
size_t ret = buf._offs;
|
|
|
|
if (ret < size) {
|
|
|
|
// if the string did fit then nul terminate
|
|
|
|
str[ret] = '\0';
|
|
|
|
} else if (size > 0) {
|
|
|
|
// if it didn't fit then terminate using passed in size
|
|
|
|
str[size-1] = 0;
|
|
|
|
}
|
|
|
|
return int(ret);
|
2013-09-21 01:25:42 -03:00
|
|
|
}
|
2016-04-12 01:39:29 -03:00
|
|
|
|
2018-02-13 21:39:37 -04:00
|
|
|
uint64_t AP_HAL::Util::get_hw_rtc() const
|
2016-04-12 01:39:29 -03:00
|
|
|
{
|
2016-06-21 07:50:01 -03:00
|
|
|
#if defined(__APPLE__) && defined(__MACH__)
|
|
|
|
struct timeval ts;
|
2016-10-30 02:24:21 -03:00
|
|
|
gettimeofday(&ts, nullptr);
|
2018-02-13 21:39:37 -04:00
|
|
|
return ((long long)((ts.tv_sec * 1000000) + ts.tv_usec));
|
|
|
|
#elif HAL_HAVE_GETTIME_SETTIME
|
2016-04-12 01:39:29 -03:00
|
|
|
struct timespec ts;
|
|
|
|
clock_gettime(CLOCK_REALTIME, &ts);
|
2016-10-14 03:29:31 -03:00
|
|
|
const uint64_t seconds = ts.tv_sec;
|
|
|
|
const uint64_t nanoseconds = ts.tv_nsec;
|
2018-02-13 21:39:37 -04:00
|
|
|
return (seconds * 1000000ULL + nanoseconds/1000ULL);
|
2016-06-21 07:50:01 -03:00
|
|
|
#endif
|
2016-04-12 01:39:29 -03:00
|
|
|
|
2018-02-13 21:39:37 -04:00
|
|
|
// no HW clock (or not one worth bothering with)
|
|
|
|
return 0;
|
2016-04-12 01:39:29 -03:00
|
|
|
}
|
|
|
|
|
2018-02-13 21:39:37 -04:00
|
|
|
void AP_HAL::Util::set_hw_rtc(uint64_t time_utc_usec)
|
2016-04-12 01:39:29 -03:00
|
|
|
{
|
2018-02-13 21:39:37 -04:00
|
|
|
#if HAL_HAVE_GETTIME_SETTIME
|
|
|
|
timespec ts;
|
|
|
|
ts.tv_sec = time_utc_usec/1000000ULL;
|
|
|
|
ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000ULL;
|
|
|
|
clock_settime(CLOCK_REALTIME, &ts);
|
|
|
|
#endif
|
2016-04-12 01:39:29 -03:00
|
|
|
}
|
2018-02-13 21:39:37 -04:00
|
|
|
|
2019-05-09 04:48:55 -03:00
|
|
|
void AP_HAL::Util::set_soft_armed(const bool b)
|
|
|
|
{
|
2019-06-17 23:57:39 -03:00
|
|
|
if (b != soft_armed) {
|
|
|
|
soft_armed = b;
|
|
|
|
last_armed_change_ms = AP_HAL::millis();
|
|
|
|
if (!was_watchdog_reset()) {
|
|
|
|
persistent_data.armed = b;
|
|
|
|
}
|
2019-05-09 04:48:55 -03:00
|
|
|
}
|
|
|
|
}
|