24 void panic(
const char *errormsg, ...)
28 va_start(ap, errormsg);
29 vdprintf(1, errormsg, ap);
58 return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
59 (state.start_time.tv_sec +
60 (state.start_time.tv_nsec*1.0e-9)));
68 return stopped_usec / 1000;
73 return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
74 (state.start_time.tv_sec +
75 (state.start_time.tv_nsec*1.0e-9)));
struct timespec start_time
void clock_gettime(uint32_t a1, void *a2)
static struct AP_HAL::@102 state
static Scheduler * from(AP_HAL::Scheduler *scheduler)
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
uint64_t stopped_clock_usec() const
#define UNUSED_RESULT(expr_)
Common definitions and utility routines for the ArduPilot libraries.
void init()
Generic board initialization function.
virtual void delay_microseconds(uint16_t us)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
AP_HAL::Scheduler * scheduler