Util.h 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171
  1. #pragma once
  2. #include <stdarg.h>
  3. #include "AP_HAL_Namespace.h"
  4. class AP_HAL::Util {
  5. public:
  6. int snprintf(char* str, size_t size,
  7. const char *format, ...);
  8. int vsnprintf(char* str, size_t size,
  9. const char *format, va_list ap);
  10. void set_soft_armed(const bool b);
  11. bool get_soft_armed() const { return soft_armed; }
  12. // return the time that the armed state last changed
  13. uint32_t get_last_armed_change() const { return last_armed_change_ms; };
  14. // return true if the reason for the reboot was a watchdog reset
  15. virtual bool was_watchdog_reset() const { return false; }
  16. // return true if safety was off and this was a watchdog reset
  17. bool was_watchdog_safety_off() const {
  18. return was_watchdog_reset() && persistent_data.safety_state == SAFETY_ARMED;
  19. }
  20. // return true if this is a watchdog reset boot and we were armed
  21. bool was_watchdog_armed() const { return was_watchdog_reset() && persistent_data.armed; }
  22. virtual const char* get_custom_log_directory() const { return nullptr; }
  23. virtual const char* get_custom_terrain_directory() const { return nullptr; }
  24. virtual const char *get_custom_storage_directory() const { return nullptr; }
  25. // get path to custom defaults file for AP_Param
  26. virtual const char* get_custom_defaults_file() const {
  27. return HAL_PARAM_DEFAULTS_PATH;
  28. }
  29. // run a debug shall on the given stream if possible. This is used
  30. // to support dropping into a debug shell to run firmware upgrade
  31. // commands
  32. virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0;
  33. enum safety_state {
  34. SAFETY_NONE, SAFETY_DISARMED, SAFETY_ARMED
  35. };
  36. /*
  37. persistent data structure. This data is restored on boot if
  38. there has been a watchdog reset. The data in this structure
  39. should only be read if was_watchdog_reset() is true
  40. Note that on STM32 this structure is limited to 76 bytes
  41. */
  42. struct PersistentData {
  43. float roll_rad, pitch_rad, yaw_rad; // attitude
  44. int32_t home_lat, home_lon, home_alt_cm; // home position
  45. bool armed; // true if vehicle was armed
  46. enum safety_state safety_state;
  47. uint32_t internal_errors;
  48. uint32_t internal_error_count;
  49. uint16_t waypoint_num;
  50. int8_t scheduler_task;
  51. uint16_t last_mavlink_msgid;
  52. uint16_t last_mavlink_cmd;
  53. uint16_t semaphore_line;
  54. uint32_t spi_count;
  55. uint32_t i2c_count;
  56. uint32_t i2c_isr_count;
  57. uint16_t fault_line;
  58. uint8_t fault_type;
  59. uint8_t fault_thd_prio;
  60. uint32_t fault_addr;
  61. uint32_t fault_icsr;
  62. };
  63. struct PersistentData persistent_data;
  64. /*
  65. return state of safety switch, if applicable
  66. */
  67. virtual enum safety_state safety_switch_state(void) { return SAFETY_NONE; }
  68. /*
  69. set HW RTC in UTC microseconds
  70. */
  71. virtual void set_hw_rtc(uint64_t time_utc_usec);
  72. /*
  73. get system clock in UTC microseconds
  74. */
  75. virtual uint64_t get_hw_rtc() const;
  76. // overwrite bootloader (probably with one from ROMFS)
  77. virtual bool flash_bootloader() { return false; }
  78. /*
  79. get system identifier (eg. serial number)
  80. return false if a system identifier is not available
  81. Buf should be filled with a printable string and must be null
  82. terminated
  83. */
  84. virtual bool get_system_id(char buf[40]) { return false; }
  85. virtual bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) { return false; }
  86. /**
  87. return commandline arguments, if available
  88. */
  89. virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
  90. /*
  91. ToneAlarm Driver
  92. */
  93. virtual bool toneAlarm_init() { return false;}
  94. virtual void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) {}
  95. /*
  96. return a stream for access to a system shell, if available
  97. */
  98. virtual AP_HAL::BetterStream *get_shell_stream() { return nullptr; }
  99. /* Support for an imu heating system */
  100. virtual void set_imu_temp(float current) {}
  101. /* Support for an imu heating system */
  102. virtual void set_imu_target_temp(int8_t *target) {}
  103. /*
  104. performance counter calls - wrapper around original PX4 interface
  105. */
  106. enum perf_counter_type {
  107. PC_COUNT, /**< count the number of times an event occurs */
  108. PC_ELAPSED, /**< measure the time elapsed performing an event */
  109. PC_INTERVAL /**< measure the interval between instances of an event */
  110. };
  111. typedef void *perf_counter_t;
  112. virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return nullptr; }
  113. virtual void perf_begin(perf_counter_t h) {}
  114. virtual void perf_end(perf_counter_t h) {}
  115. virtual void perf_count(perf_counter_t h) {}
  116. // allocate and free DMA-capable memory if possible. Otherwise return normal memory
  117. enum Memory_Type {
  118. MEM_DMA_SAFE,
  119. MEM_FAST
  120. };
  121. virtual void *malloc_type(size_t size, Memory_Type mem_type) { return calloc(1, size); }
  122. virtual void free_type(void *ptr, size_t size, Memory_Type mem_type) { return free(ptr); }
  123. #ifdef ENABLE_HEAP
  124. // heap functions, note that a heap once alloc'd cannot be dealloc'd
  125. virtual void *allocate_heap_memory(size_t size) = 0;
  126. virtual void *heap_realloc(void *heap, void *ptr, size_t new_size) = 0;
  127. #endif // ENABLE_HEAP
  128. /**
  129. how much free memory do we have in bytes. If unknown return 4096
  130. */
  131. virtual uint32_t available_memory(void) { return 4096; }
  132. /*
  133. initialise (or re-initialise) filesystem storage
  134. */
  135. virtual bool fs_init(void) { return false; }
  136. protected:
  137. // we start soft_armed false, so that actuators don't send any
  138. // values until the vehicle code has fully started
  139. bool soft_armed = false;
  140. uint32_t last_armed_change_ms;
  141. };