APM:Libraries
Util.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdarg.h>
4 #include "AP_HAL_Namespace.h"
5 
6 class AP_HAL::Util {
7 public:
8  int snprintf(char* str, size_t size,
9  const char *format, ...);
10 
11  int vsnprintf(char* str, size_t size,
12  const char *format, va_list ap);
13 
14  void set_soft_armed(const bool b) { soft_armed = b; }
15  bool get_soft_armed() const { return soft_armed; }
16 
17  void set_capabilities(uint64_t cap) { capabilities |= cap; }
18  void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); }
19  uint64_t get_capabilities() const { return capabilities; }
20 
21  virtual const char* get_custom_log_directory() const { return nullptr; }
22  virtual const char* get_custom_terrain_directory() const { return nullptr; }
23  virtual const char *get_custom_storage_directory() const { return nullptr; }
24 
25  // get path to custom defaults file for AP_Param
26  virtual const char* get_custom_defaults_file() const {
28  }
29 
30  // run a debug shall on the given stream if possible. This is used
31  // to support dropping into a debug shell to run firmware upgrade
32  // commands
33  virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0;
34 
35  enum safety_state {
37  };
38 
39  /*
40  return state of safety switch, if applicable
41  */
42  virtual enum safety_state safety_switch_state(void) { return SAFETY_NONE; }
43 
44  /*
45  set system clock in UTC microseconds
46  */
47  virtual void set_system_clock(uint64_t time_utc_usec) {}
48 
49  /*
50  get system clock in UTC milliseconds
51  */
52  uint64_t get_system_clock_ms() const;
53 
54  /*
55  get system time in UTC hours, minutes, seconds and milliseconds
56  */
57  void get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const;
58 
59  uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const;
60 
61  /*
62  get system identifier (eg. serial number)
63  return false if a system identifier is not available
64 
65  Buf should be filled with a printable string and must be null
66  terminated
67  */
68  virtual bool get_system_id(char buf[40]) { return false; }
69 
73  virtual void commandline_arguments(uint8_t &argc, char * const *&argv) { argc = 0; }
74 
75  /*
76  ToneAlarm Driver
77  */
78  virtual bool toneAlarm_init() { return false;}
79  virtual void toneAlarm_set_tune(uint8_t tune) {}
80  virtual void _toneAlarm_timer_tick() {}
81 
82  /*
83  return a stream for access to a system shell, if available
84  */
85  virtual AP_HAL::BetterStream *get_shell_stream() { return nullptr; }
86 
87  /* Support for an imu heating system */
88  virtual void set_imu_temp(float current) {}
89 
90  /* Support for an imu heating system */
91  virtual void set_imu_target_temp(int8_t *target) {}
92 
93  /*
94  performance counter calls - wrapper around original PX4 interface
95  */
100  };
101  typedef void *perf_counter_t;
102  virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return nullptr; }
103  virtual void perf_begin(perf_counter_t h) {}
104  virtual void perf_end(perf_counter_t h) {}
105  virtual void perf_count(perf_counter_t h) {}
106 
107  // create a new semaphore
108  virtual Semaphore *new_semaphore(void) { return nullptr; }
109 
110  // allocate and free DMA-capable memory if possible. Otherwise return normal memory
111  enum Memory_Type {
114  };
115  virtual void *malloc_type(size_t size, Memory_Type mem_type) { return calloc(1, size); }
116  virtual void free_type(void *ptr, size_t size, Memory_Type mem_type) { return free(ptr); }
117 
121  virtual uint32_t available_memory(void) { return 4096; }
122 protected:
123  // we start soft_armed false, so that actuators don't send any
124  // values until the vehicle code has fully started
125  bool soft_armed = false;
126  uint64_t capabilities = 0;
127 };
virtual uint32_t available_memory(void)
Definition: Util.h:121
bool get_soft_armed() const
Definition: Util.h:15
uint64_t capabilities
Definition: Util.h:126
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
virtual const char * get_custom_log_directory() const
Definition: Util.h:21
virtual void _toneAlarm_timer_tick()
Definition: Util.h:80
void clear_capabilities(uint64_t cap)
Definition: Util.h:18
virtual void set_imu_temp(float current)
Definition: Util.h:88
virtual void set_imu_target_temp(int8_t *target)
Definition: Util.h:91
void set_capabilities(uint64_t cap)
Definition: Util.h:17
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
Definition: Util.cpp:99
virtual bool run_debug_shell(AP_HAL::BetterStream *stream)=0
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
const char * name
Definition: BusTest.cpp:11
#define HAL_PARAM_DEFAULTS_PATH
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
Definition: Util.h:116
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
virtual void toneAlarm_set_tune(uint8_t tune)
Definition: Util.h:79
int vsnprintf(char *str, size_t size, const char *format, va_list ap)
Definition: Util.cpp:53
void get_system_clock_utc(int32_t &hour, int32_t &min, int32_t &sec, int32_t &ms) const
Definition: Util.cpp:80
virtual const char * get_custom_terrain_directory() const
Definition: Util.h:22
void * perf_counter_t
Definition: Util.h:101
perf_counter_type
Definition: Util.h:96
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
virtual bool get_system_id(char buf[40])
Definition: Util.h:68
safety_state
Definition: Util.h:35
virtual void set_system_clock(uint64_t time_utc_usec)
Definition: Util.h:47
void free(void *ptr)
Definition: malloc.c:81
virtual const char * get_custom_storage_directory() const
Definition: Util.h:23
virtual const char * get_custom_defaults_file() const
Definition: Util.h:26
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
void set_soft_armed(const bool b)
Definition: Util.h:14
int snprintf(char *str, size_t size, const char *format,...)
Definition: Util.cpp:44
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
virtual AP_HAL::BetterStream * get_shell_stream()
Definition: Util.h:85
uint64_t get_capabilities() const
Definition: Util.h:19
virtual void commandline_arguments(uint8_t &argc, char *const *&argv)
Definition: Util.h:73
uint64_t get_system_clock_ms() const
Definition: Util.cpp:63
bool soft_armed
Definition: Util.h:125
virtual bool toneAlarm_init()
Definition: Util.h:78
virtual void perf_count(perf_counter_t h)
Definition: Util.h:105