APM:Libraries
system.cpp
Go to the documentation of this file.
1 #include <stdarg.h>
2 #include <stdio.h>
3 #include <sys/time.h>
4 #include <unistd.h>
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_HAL/system.h>
10 
11 extern const AP_HAL::HAL& hal;
12 
13 namespace AP_HAL {
14 
15 static struct {
16  struct timespec start_time;
17 } state;
18 
19 void init()
20 {
21  clock_gettime(CLOCK_MONOTONIC, &state.start_time);
22 }
23 
24 void panic(const char *errormsg, ...)
25 {
26  va_list ap;
27 
28  va_start(ap, errormsg);
29  vdprintf(1, errormsg, ap);
30  va_end(ap);
31  UNUSED_RESULT(write(1, "\n", 1));
32 
33  hal.rcin->teardown();
34  hal.scheduler->delay_microseconds(10000);
35  exit(1);
36 }
37 
38 uint32_t micros()
39 {
40  return micros64() & 0xFFFFFFFF;
41 }
42 
43 uint32_t millis()
44 {
45  return millis64() & 0xFFFFFFFF;
46 }
47 
48 uint64_t micros64()
49 {
50  const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
51  uint64_t stopped_usec = scheduler->stopped_clock_usec();
52  if (stopped_usec) {
53  return stopped_usec;
54  }
55 
56  struct timespec ts;
57  clock_gettime(CLOCK_MONOTONIC, &ts);
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)));
61 }
62 
63 uint64_t millis64()
64 {
65  const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
66  uint64_t stopped_usec = scheduler->stopped_clock_usec();
67  if (stopped_usec) {
68  return stopped_usec / 1000;
69  }
70 
71  struct timespec ts;
72  clock_gettime(CLOCK_MONOTONIC, &ts);
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)));
76 }
77 
78 } // namespace AP_HAL
struct timespec start_time
Definition: system.cpp:16
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
static struct AP_HAL::@102 state
static Scheduler * from(AP_HAL::Scheduler *scheduler)
Definition: Scheduler.h:23
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 stopped_clock_usec() const
Definition: Scheduler.h:46
uint64_t millis64()
Definition: system.cpp:167
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
#define UNUSED_RESULT(expr_)
Definition: AP_Common.h:104
Common definitions and utility routines for the ArduPilot libraries.
virtual void teardown()
Definition: RCInput.h:17
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
AP_HAL::RCInput * rcin
Definition: HAL.h:112
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114