2015-11-11 09:43:18 -04:00
|
|
|
#include <stdarg.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-11-19 23:24:56 -04:00
|
|
|
#include <AP_HAL/system.h>
|
|
|
|
|
2015-11-11 09:43:18 -04:00
|
|
|
#include "Scheduler.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
using HALSITL::Scheduler;
|
2015-11-11 09:43:18 -04:00
|
|
|
|
2015-11-19 23:24:56 -04:00
|
|
|
namespace AP_HAL {
|
|
|
|
|
2015-11-11 09:43:18 -04:00
|
|
|
static struct {
|
|
|
|
struct timeval start_time;
|
|
|
|
} state;
|
|
|
|
|
2015-11-19 23:24:56 -04:00
|
|
|
void init()
|
|
|
|
{
|
2016-10-30 02:24:21 -03:00
|
|
|
gettimeofday(&state.start_time, nullptr);
|
2015-11-11 09:43:18 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void panic(const char *errormsg, ...)
|
|
|
|
{
|
|
|
|
va_list ap;
|
|
|
|
|
2016-11-17 02:06:22 -04:00
|
|
|
fflush(stdout);
|
2015-11-11 09:43:18 -04:00
|
|
|
va_start(ap, errormsg);
|
|
|
|
vprintf(errormsg, ap);
|
|
|
|
va_end(ap);
|
|
|
|
printf("\n");
|
|
|
|
|
|
|
|
for(;;);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t micros()
|
|
|
|
{
|
|
|
|
return micros64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t millis()
|
|
|
|
{
|
|
|
|
return millis64() & 0xFFFFFFFF;
|
|
|
|
}
|
|
|
|
|
2018-12-10 18:44:05 -04:00
|
|
|
/*
|
|
|
|
we define a millis16() here to avoid an issue with sitl builds in cygwin
|
|
|
|
*/
|
|
|
|
uint16_t millis16()
|
|
|
|
{
|
|
|
|
return millis64() & 0xFFFF;
|
|
|
|
}
|
|
|
|
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t micros64()
|
|
|
|
{
|
2016-01-10 02:23:32 -04:00
|
|
|
const HALSITL::Scheduler* scheduler = HALSITL::Scheduler::from(hal.scheduler);
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t stopped_usec = scheduler->stopped_clock_usec();
|
|
|
|
if (stopped_usec) {
|
|
|
|
return stopped_usec;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct timeval tp;
|
2016-10-30 02:24:21 -03:00
|
|
|
gettimeofday(&tp, nullptr);
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_usec * 1.0e-6)));
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint64_t millis64()
|
|
|
|
{
|
2016-01-10 02:23:32 -04:00
|
|
|
const HALSITL::Scheduler* scheduler = HALSITL::Scheduler::from(hal.scheduler);
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t stopped_usec = scheduler->stopped_clock_usec();
|
|
|
|
if (stopped_usec) {
|
|
|
|
return stopped_usec / 1000;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct timeval tp;
|
2016-10-30 02:24:21 -03:00
|
|
|
gettimeofday(&tp, nullptr);
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) -
|
|
|
|
(state.start_time.tv_sec +
|
|
|
|
(state.start_time.tv_usec*1.0e-6)));
|
|
|
|
return ret;
|
2015-11-19 23:24:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
} // namespace AP_HAL
|