18 #if AP_MODULE_SUPPORTED 25 #if defined(HAVE_LIBDL) 32 struct AP_Module::hook_list *AP_Module::hooks[NUM_HOOKS];
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",
45 void AP_Module::module_scan(
const char *path)
47 #if defined(HAVE_LIBDL) 48 void *m = dlopen(path, RTLD_NOW);
50 printf(
"dlopen(%s) -> %s\n", path, dlerror());
53 uint8_t found_hooks = 0;
54 for (uint16_t i=0; i<NUM_HOOKS; i++) {
55 void *s = dlsym(m, hook_names[i]);
58 struct hook_list *h =
new hook_list;
60 AP_HAL::panic(
"Failed to allocate hook for %s", hook_names[i]);
68 if (found_hooks == 0) {
72 printf(
"AP_Module: Loaded %u hooks from %s\n", (
unsigned)found_hooks, path);
82 #if AP_MODULE_SUPPORTED 91 const char *extension = strrchr(de->d_name,
'.');
92 if (extension ==
nullptr || strcmp(extension,
".so") != 0) {
96 if (
asprintf(&path,
"%s/%s", module_path, de->d_name) == -1) {
110 void AP_Module::call_hook_setup_start(
void)
112 #if AP_MODULE_SUPPORTED 114 for (
const struct hook_list *h=hooks[HOOK_SETUP_START]; h; h=h->next) {
124 void AP_Module::call_hook_setup_complete(
void)
126 #if AP_MODULE_SUPPORTED 128 for (
const struct hook_list *h=hooks[HOOK_SETUP_COMPLETE]; h; h=h->next) {
140 #if AP_MODULE_SUPPORTED 141 if (hooks[HOOK_AHRS_UPDATE] ==
nullptr) {
163 state.
quat[0] = q[0];
164 state.
quat[1] = q[1];
165 state.
quat[2] = q[2];
166 state.
quat[3] = q[3];
219 for (
const struct hook_list *h=hooks[HOOK_AHRS_UPDATE]; h; h=h->next) {
230 void AP_Module::call_hook_gyro_sample(uint8_t instance,
float dt,
const Vector3f &gyro)
232 #if AP_MODULE_SUPPORTED 233 if (hooks[HOOK_GYRO_SAMPLE] ==
nullptr) {
246 state.
gyro[0] = gyro[0];
247 state.
gyro[1] = gyro[1];
248 state.
gyro[2] = gyro[2];
250 for (
const struct hook_list *h=hooks[HOOK_GYRO_SAMPLE]; h; h=h->next) {
260 void AP_Module::call_hook_accel_sample(uint8_t instance,
float dt,
const Vector3f &accel,
bool fsync_set)
262 #if AP_MODULE_SUPPORTED 263 if (hooks[HOOK_ACCEL_SAMPLE] ==
nullptr) {
276 state.
accel[0] = accel[0];
277 state.
accel[1] = accel[1];
278 state.
accel[2] = accel[2];
281 for (
const struct hook_list *h=hooks[HOOK_ACCEL_SAMPLE]; h; h=h->next) {
288 #endif // AP_MODULE_SUPPORTED
int printf(const char *fmt,...)
bool initialised() const override
dirent_t * readdir(DIR *dirp)
const Vector3f & get_gyro(void) const override
bool healthy() const override
const Vector3f & get_accel_ef(uint8_t i) const override
uint32_t structure_version
uint32_t structure_version
void from_rotation_matrix(const Matrix3f &m)
#define gyro_sample_version
int32_t lat
param 3 - Latitude * 10**7
bool get_origin(Location &ret) const override
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
uint32_t structure_version
void(* ap_hook_gyro_sample_fn_t)(const struct gyro_sample *)
uint8_t get_primary_accel_index(void) const override
bool get_position(struct Location &loc) const override
struct AHRS_state::@133 origin
struct AHRS_state::@134 position
void(* ap_hook_setup_complete_fn_t)(uint64_t)
int32_t lng
param 4 - Longitude * 10**7
int closedir(DIR *dirp)
POSIX closedir.
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.
void(* ap_hook_accel_sample_fn_t)(const struct accel_sample *)
int asprintf(char **strp, const char *fmt,...)
bool get_relative_position_NED_origin(Vector3f &vec) const override
#define AHRS_state_version
DIR * opendir(const char *pathdir)
void panic(const char *errormsg,...) FMT_PRINTF(1
bool get_velocity_NED(Vector3f &vec) const override
#define accel_sample_version
void(* ap_hook_setup_start_fn_t)(uint64_t)
const Vector3f & get_gyro_drift(void) const override