system.cpp 1.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  1. #include <stdarg.h>
  2. #include <stdio.h>
  3. #include <sys/time.h>
  4. #include <unistd.h>
  5. #include <AP_Common/AP_Common.h>
  6. #include <AP_HAL/AP_HAL.h>
  7. #include <AP_HAL/system.h>
  8. #include <AP_HAL_Linux/Scheduler.h>
  9. extern const AP_HAL::HAL& hal;
  10. namespace AP_HAL {
  11. static struct {
  12. struct timespec start_time;
  13. } state;
  14. void init()
  15. {
  16. clock_gettime(CLOCK_MONOTONIC, &state.start_time);
  17. }
  18. void panic(const char *errormsg, ...)
  19. {
  20. va_list ap;
  21. va_start(ap, errormsg);
  22. vdprintf(1, errormsg, ap);
  23. va_end(ap);
  24. UNUSED_RESULT(write(1, "\n", 1));
  25. hal.rcin->teardown();
  26. hal.scheduler->delay_microseconds(10000);
  27. exit(1);
  28. }
  29. uint32_t micros()
  30. {
  31. return micros64() & 0xFFFFFFFF;
  32. }
  33. uint32_t millis()
  34. {
  35. return millis64() & 0xFFFFFFFF;
  36. }
  37. uint64_t micros64()
  38. {
  39. const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
  40. uint64_t stopped_usec = scheduler->stopped_clock_usec();
  41. if (stopped_usec) {
  42. return stopped_usec;
  43. }
  44. struct timespec ts;
  45. clock_gettime(CLOCK_MONOTONIC, &ts);
  46. return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
  47. (state.start_time.tv_sec +
  48. (state.start_time.tv_nsec*1.0e-9)));
  49. }
  50. uint64_t millis64()
  51. {
  52. const Linux::Scheduler* scheduler = Linux::Scheduler::from(hal.scheduler);
  53. uint64_t stopped_usec = scheduler->stopped_clock_usec();
  54. if (stopped_usec) {
  55. return stopped_usec / 1000;
  56. }
  57. struct timespec ts;
  58. clock_gettime(CLOCK_MONOTONIC, &ts);
  59. return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) -
  60. (state.start_time.tv_sec +
  61. (state.start_time.tv_nsec*1.0e-9)));
  62. }
  63. } // namespace AP_HAL