AP_Module.cpp 7.6 KB

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