APM:Libraries
AP_Module.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
17 
18 #if AP_MODULE_SUPPORTED
19 
20 /*
21  support for external modules
22  */
23 
24 #include <stdio.h>
25 #if defined(HAVE_LIBDL)
26 #include <dirent.h>
27 #include <dlfcn.h>
28 #endif
29 #include <AP_Module/AP_Module.h>
31 
32 struct AP_Module::hook_list *AP_Module::hooks[NUM_HOOKS];
33 
34 const char *AP_Module::hook_names[AP_Module::NUM_HOOKS] = {
35  "ap_hook_setup_start",
36  "ap_hook_setup_complete",
37  "ap_hook_AHRS_update",
38  "ap_hook_gyro_sample",
39  "ap_hook_accel_sample",
40 };
41 
42 /*
43  scan a module for hook symbols
44  */
45 void AP_Module::module_scan(const char *path)
46 {
47 #if defined(HAVE_LIBDL)
48  void *m = dlopen(path, RTLD_NOW);
49  if (m == nullptr) {
50  printf("dlopen(%s) -> %s\n", path, dlerror());
51  return;
52  }
53  uint8_t found_hooks = 0;
54  for (uint16_t i=0; i<NUM_HOOKS; i++) {
55  void *s = dlsym(m, hook_names[i]);
56  if (s != nullptr) {
57  // found a hook in this module, add it to the list
58  struct hook_list *h = new hook_list;
59  if (h == nullptr) {
60  AP_HAL::panic("Failed to allocate hook for %s", hook_names[i]);
61  }
62  h->next = hooks[i];
63  h->symbol = s;
64  hooks[i] = h;
65  found_hooks++;
66  }
67  }
68  if (found_hooks == 0) {
69  // we don't need this module
70  dlclose(m);
71  } else {
72  printf("AP_Module: Loaded %u hooks from %s\n", (unsigned)found_hooks, path);
73  }
74 #endif
75 }
76 
77 /*
78  initialise AP_Module, looking for shared libraries in the given module path
79 */
80 void AP_Module::init(const char *module_path)
81 {
82 #if AP_MODULE_SUPPORTED
83  // scan through module directory looking for *.so
84  DIR *d;
85  struct dirent *de;
86  d = opendir(module_path);
87  if (d == nullptr) {
88  return;
89  }
90  while ((de = readdir(d))) {
91  const char *extension = strrchr(de->d_name, '.');
92  if (extension == nullptr || strcmp(extension, ".so") != 0) {
93  continue;
94  }
95  char *path = nullptr;
96  if (asprintf(&path, "%s/%s", module_path, de->d_name) == -1) {
97  continue;
98  }
99  module_scan(path);
100  free(path);
101  }
102  closedir(d);
103 #endif
104 }
105 
106 
107 /*
108  call any setup_start hooks
109 */
110 void AP_Module::call_hook_setup_start(void)
111 {
112 #if AP_MODULE_SUPPORTED
113  uint64_t now = AP_HAL::micros64();
114  for (const struct hook_list *h=hooks[HOOK_SETUP_START]; h; h=h->next) {
115  ap_hook_setup_start_fn_t fn = reinterpret_cast<ap_hook_setup_start_fn_t>(h->symbol);
116  fn(now);
117  }
118 #endif
119 }
120 
121 /*
122  call any setup_complete hooks
123 */
124 void AP_Module::call_hook_setup_complete(void)
125 {
126 #if AP_MODULE_SUPPORTED
127  uint64_t now = AP_HAL::micros64();
128  for (const struct hook_list *h=hooks[HOOK_SETUP_COMPLETE]; h; h=h->next) {
129  ap_hook_setup_complete_fn_t fn = reinterpret_cast<ap_hook_setup_complete_fn_t>(h->symbol);
130  fn(now);
131  }
132 #endif
133 }
134 
135 /*
136  call any AHRS_update hooks
137 */
138 void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
139 {
140 #if AP_MODULE_SUPPORTED
141  if (hooks[HOOK_AHRS_UPDATE] == nullptr) {
142  // avoid filling in AHRS_state
143  return;
144  }
145 
146  /*
147  construct AHRS_state structure
148  */
149  struct AHRS_state state {};
151  state.time_us = AP_HAL::micros64();
152 
153  if (!ahrs.initialised()) {
155  } else if (ahrs.healthy()) {
156  state.status = AHRS_STATUS_HEALTHY;
157  } else {
159  }
160 
161  Quaternion q;
163  state.quat[0] = q[0];
164  state.quat[1] = q[1];
165  state.quat[2] = q[2];
166  state.quat[3] = q[3];
167 
168  state.eulers[0] = ahrs.roll;
169  state.eulers[1] = ahrs.pitch;
170  state.eulers[2] = ahrs.yaw;
171 
172  Location loc;
173  if (ahrs.get_origin(loc)) {
174  state.origin.initialised = true;
175  state.origin.latitude = loc.lat;
176  state.origin.longitude = loc.lng;
177  state.origin.altitude = loc.alt*0.01f;
178  }
179 
180  if (ahrs.get_position(loc)) {
181  state.position.available = true;
182  state.position.latitude = loc.lat;
183  state.position.longitude = loc.lng;
184  state.position.altitude = loc.alt*0.01f;
185  }
186 
187  Vector3f pos;
188  if (ahrs.get_relative_position_NED_origin(pos)) {
189  state.relative_position[0] = pos[0];
190  state.relative_position[1] = pos[1];
191  state.relative_position[2] = pos[2];
192  }
193 
194  const Vector3f &gyro = ahrs.get_gyro();
195  state.gyro_rate[0] = gyro[0];
196  state.gyro_rate[1] = gyro[1];
197  state.gyro_rate[2] = gyro[2];
198 
199  const Vector3f &accel_ef = ahrs.get_accel_ef();
200  state.accel_ef[0] = accel_ef[0];
201  state.accel_ef[1] = accel_ef[0];
202  state.accel_ef[2] = accel_ef[0];
203 
204  state.primary_accel = ahrs.get_primary_accel_index();
205  state.primary_gyro = ahrs.get_primary_gyro_index();
206 
207  const Vector3f &gyro_bias = ahrs.get_gyro_drift();
208  state.gyro_bias[0] = gyro_bias[0];
209  state.gyro_bias[1] = gyro_bias[1];
210  state.gyro_bias[2] = gyro_bias[2];
211 
212  Vector3f vel;
213  if (ahrs.get_velocity_NED(vel)) {
214  state.velocity_ned[0] = vel.x;
215  state.velocity_ned[1] = vel.y;
216  state.velocity_ned[2] = vel.z;
217  }
218 
219  for (const struct hook_list *h=hooks[HOOK_AHRS_UPDATE]; h; h=h->next) {
220  ap_hook_AHRS_update_fn_t fn = reinterpret_cast<ap_hook_AHRS_update_fn_t>(h->symbol);
221  fn(&state);
222  }
223 #endif
224 }
225 
226 
227 /*
228  call any gyro_sample hooks
229 */
230 void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f &gyro)
231 {
232 #if AP_MODULE_SUPPORTED
233  if (hooks[HOOK_GYRO_SAMPLE] == nullptr) {
234  // avoid filling in struct
235  return;
236  }
237 
238  /*
239  construct gyro_sample structure
240  */
241  struct gyro_sample state {};
243  state.time_us = AP_HAL::micros64();
244  state.instance = instance;
245  state.delta_time = dt;
246  state.gyro[0] = gyro[0];
247  state.gyro[1] = gyro[1];
248  state.gyro[2] = gyro[2];
249 
250  for (const struct hook_list *h=hooks[HOOK_GYRO_SAMPLE]; h; h=h->next) {
251  ap_hook_gyro_sample_fn_t fn = reinterpret_cast<ap_hook_gyro_sample_fn_t>(h->symbol);
252  fn(&state);
253  }
254 #endif
255 }
256 
257 /*
258  call any accel_sample hooks
259 */
260 void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3f &accel, bool fsync_set)
261 {
262 #if AP_MODULE_SUPPORTED
263  if (hooks[HOOK_ACCEL_SAMPLE] == nullptr) {
264  // avoid filling in struct
265  return;
266  }
267 
268  /*
269  construct accel_sample structure
270  */
271  struct accel_sample state {};
273  state.time_us = AP_HAL::micros64();
274  state.instance = instance;
275  state.delta_time = dt;
276  state.accel[0] = accel[0];
277  state.accel[1] = accel[1];
278  state.accel[2] = accel[2];
279  state.fsync_set = fsync_set;
280 
281  for (const struct hook_list *h=hooks[HOOK_ACCEL_SAMPLE]; h; h=h->next) {
282  ap_hook_accel_sample_fn_t fn = reinterpret_cast<ap_hook_accel_sample_fn_t>(h->symbol);
283  fn(&state);
284  }
285 #endif
286 }
287 
288 #endif // AP_MODULE_SUPPORTED
int printf(const char *fmt,...)
Definition: stdio.c:113
bool initialised() const override
float roll
Definition: AP_AHRS.h:224
dirent_t * readdir(DIR *dirp)
Definition: posix.c:1768
const Vector3f & get_gyro(void) const override
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
bool healthy() const override
const Vector3f & get_accel_ef(uint8_t i) const override
uint32_t structure_version
float pitch
Definition: AP_AHRS.h:225
float yaw
Definition: AP_AHRS.h:226
uint32_t structure_version
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
#define gyro_sample_version
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool get_origin(Location &ret) const override
Definition: ff.h:201
void(* ap_hook_AHRS_update_fn_t)(const struct AHRS_state *)
float relative_position[3]
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
uint32_t structure_version
enum AHRS_status status
void(* ap_hook_gyro_sample_fn_t)(const struct gyro_sample *)
T y
Definition: vector3.h:67
uint8_t get_primary_accel_index(void) const override
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
bool get_position(struct Location &loc) const override
struct AHRS_state::@133 origin
struct AHRS_state::@134 position
void free(void *ptr)
Definition: malloc.c:81
void(* ap_hook_setup_complete_fn_t)(uint64_t)
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
int closedir(DIR *dirp)
POSIX closedir.
Definition: posix.c:1730
uint8_t get_primary_gyro_index(void) const override
const Matrix3f & get_rotation_body_to_ned(void) const override
void init()
Generic board initialization function.
Definition: system.cpp:136
void(* ap_hook_accel_sample_fn_t)(const struct accel_sample *)
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
bool get_relative_position_NED_origin(Vector3f &vec) const override
#define AHRS_state_version
DIR * opendir(const char *pathdir)
Definition: posix.c:1749
float velocity_ned[3]
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool get_velocity_NED(Vector3f &vec) const override
#define accel_sample_version
T x
Definition: vector3.h:67
void(* ap_hook_setup_start_fn_t)(uint64_t)
const Vector3f & get_gyro_drift(void) const override