APM:Libraries
Util.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
5 #include "Semaphores.h"
6 
8 public:
9  size_t write(uint8_t);
10  size_t write(const uint8_t *buffer, size_t size);
11  int16_t read() override;
12  uint32_t available() override;
13  uint32_t txspace() override;
14 private:
15  int shell_stdin = -1;
16  int shell_stdout = -1;
17  pthread_t shell_thread_ctx;
18 
19  struct {
20  int in = -1;
21  int out = -1;
22  } child;
23  bool showed_memory_warning = false;
24  bool showed_armed_warning = false;
25 
26  void start_shell(void);
27  static void shell_thread(void *arg);
28 };
29 
31 public:
32  VRBRAINUtil(void);
33  bool run_debug_shell(AP_HAL::BetterStream *stream);
34 
35  enum safety_state safety_switch_state(void);
36 
37  /*
38  set system clock in UTC microseconds
39  */
40  void set_system_clock(uint64_t time_utc_usec);
41 
42  /*
43  get system identifier (STM32 serial number)
44  */
45  bool get_system_id(char buf[40]);
46 
47  uint32_t available_memory(void) override;
48 
49  /*
50  return a stream for access to nsh shell
51  */
52  AP_HAL::BetterStream *get_shell_stream() { return &_shell_stream; }
53  perf_counter_t perf_alloc(perf_counter_type t, const char *name) override;
54  void perf_begin(perf_counter_t ) override;
55  void perf_end(perf_counter_t) override;
56  void perf_count(perf_counter_t) override;
57 
58  // create a new semaphore
59  AP_HAL::Semaphore *new_semaphore(void) override { return new VRBRAIN::Semaphore; }
60 
61  void set_imu_temp(float current) override;
62  void set_imu_target_temp(int8_t *target) override;
63 
64  // allocate and free DMA-capable memory if possible. Otherwise return normal memory
65  void *malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override;
66  void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override;
67 
68 private:
71 
72  struct {
73  int8_t *target;
74  float integrator;
75  uint16_t count;
76  float sum;
77  uint32_t last_update_ms;
78  int fd = -1;
79  } _heater;
80 };
AP_HAL::BetterStream * get_shell_stream()
Definition: Util.h:52
int16_t read() override
bool showed_armed_warning
Definition: Util.h:24
int _safety_handle
Definition: Util.h:69
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
pthread_t shell_thread_ctx
Definition: Util.h:17
VRBRAIN::NSHShellStream _shell_stream
Definition: Util.h:70
const char * name
Definition: BusTest.cpp:11
uint32_t txspace() override
uint32_t available() override
float integrator
Definition: Util.h:74
void * perf_counter_t
Definition: Util.h:101
perf_counter_type
Definition: Util.h:96
AP_HAL::Semaphore * new_semaphore(void) override
Definition: Util.h:59
bool showed_memory_warning
Definition: Util.h:23
safety_state
Definition: Util.h:35
uint32_t last_update_ms
Definition: Util.h:77
uint16_t count
Definition: Util.h:75
struct VRBRAIN::NSHShellStream::@117 child
static void shell_thread(void *arg)
int8_t * target
Definition: Util.h:73