APM:Libraries
system.cpp
Go to the documentation of this file.
1 #include <stdarg.h>
2 #include <stdio.h>
3 
4 #include <drivers/drv_hrt.h>
5 
6 #include <AP_HAL/AP_HAL.h>
7 #include <AP_HAL/system.h>
8 
9 extern const AP_HAL::HAL& hal;
10 
11 extern bool _px4_thread_should_exit;
12 
13 namespace AP_HAL {
14 
15 void init()
16 {
17 }
18 
19 void panic(const char *errormsg, ...)
20 {
21  va_list ap;
22 
23  va_start(ap, errormsg);
24  vdprintf(1, errormsg, ap);
25  va_end(ap);
26  write(1, "\n", 1);
27 
28  hal.scheduler->delay_microseconds(10000);
30  exit(1);
31 }
32 
33 uint32_t micros()
34 {
35  return micros64() & 0xFFFFFFFF;
36 }
37 
38 uint32_t millis()
39 {
40  return millis64() & 0xFFFFFFFF;
41 }
42 
43 uint64_t micros64()
44 {
45  return hrt_absolute_time();
46 }
47 
48 uint64_t millis64()
49 {
50  return micros64() / 1000;
51 }
52 
53 } // namespace AP_HAL
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
uint64_t millis64()
Definition: system.cpp:167
bool _px4_thread_should_exit
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint32_t millis()
Definition: system.cpp:157
uint64_t micros64()
Definition: system.cpp:162
void init()
Generic board initialization function.
Definition: system.cpp:136
virtual void delay_microseconds(uint16_t us)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114