2015-11-11 10:02:43 -04:00
|
|
|
#include <stdarg.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <sys/time.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
2016-06-21 16:42:17 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-11-11 10:02:43 -04:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-11-19 23:24:56 -04:00
|
|
|
#include <AP_HAL/system.h>
|
2015-11-11 10:02:43 -04:00
|
|
|
#include <AP_HAL_Linux/Scheduler.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2015-11-19 23:24:56 -04:00
|
|
|
|
|
|
|
namespace AP_HAL {
|
|
|
|
|
2015-11-11 10:02:43 -04:00
|
|
|
static struct {
|
|
|
|
struct timespec start_time;
|
|
|
|
} state;
|
|
|
|
|
2015-11-19 23:24:56 -04:00
|
|
|
void init()
|
|
|
|
{
|
2015-11-11 10:02:43 -04:00
|
|
|
clock_gettime(CLOCK_MONOTONIC, &state.start_time);
|
|
|
|
}
|
|
|
|
|
|
|
|
void panic(const char *errormsg, ...)
|
|
|
|
{
|
|
|
|
va_list ap;
|
|
|
|
|
|
|
|
va_start(ap, errormsg);
|
|
|
|
vdprintf(1, errormsg, ap);
|
|
|
|
va_end(ap);
|
2016-06-21 16:42:17 -03:00
|
|
|
UNUSED_RESULT(write(1, "\n", 1));
|
2015-11-11 10:02:43 -04:00
|
|
|
|
2020-03-05 21:48:40 -04:00
|
|
|
if (hal.rcin != nullptr) {
|
|
|
|
hal.rcin->teardown();
|
|
|
|
}
|
|
|
|
if (hal.scheduler != nullptr) {
|
|
|
|
hal.scheduler->delay_microseconds(10000);
|
|
|
|
}
|
2015-11-11 10:02:43 -04:00
|
|
|
exit(1);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t micros()
|
|
|
|
{
|
|
|
|
return micros64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t millis()
|
|
|
|
{
|
|
|
|
return millis64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint64_t micros64()
|
|
|
|
{
|
|
|
|
const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
|
|
|
|
uint64_t stopped_usec = scheduler->stopped_clock_usec();
|
|
|
|
if (stopped_usec) {
|
|
|
|
return stopped_usec;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct timespec ts;
|
|
|
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
|
|
|
return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_nsec*1.0e-9)));
|
|
|
|
}
|
|
|
|
|
|
|
|
uint64_t millis64()
|
|
|
|
{
|
|
|
|
const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
|
|
|
|
uint64_t stopped_usec = scheduler->stopped_clock_usec();
|
|
|
|
if (stopped_usec) {
|
|
|
|
return stopped_usec / 1000;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct timespec ts;
|
|
|
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
|
|
|
return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_nsec*1.0e-9)));
|
2015-11-19 23:24:56 -04:00
|
|
|
}
|
|
|
|
|
2020-05-31 09:25:55 -03:00
|
|
|
|
|
|
|
uint32_t native_micros()
|
|
|
|
{
|
|
|
|
return native_micros64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t native_millis()
|
|
|
|
{
|
|
|
|
return native_millis64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
we define a millis16() here to avoid an issue with sitl builds in cygwin
|
|
|
|
*/
|
|
|
|
uint16_t native_millis16()
|
|
|
|
{
|
|
|
|
return native_millis64() & 0xFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
uint64_t native_micros64()
|
|
|
|
{
|
|
|
|
struct timespec ts;
|
|
|
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
|
|
|
return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_nsec*1.0e-9)));
|
|
|
|
}
|
|
|
|
|
|
|
|
uint64_t native_millis64()
|
|
|
|
{
|
|
|
|
struct timespec ts;
|
|
|
|
clock_gettime(CLOCK_MONOTONIC, &ts);
|
|
|
|
return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_nsec*1.0e-9)));
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-11-19 23:24:56 -04:00
|
|
|
} // namespace AP_HAL
|