12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #if AP_MODULE_SUPPORTED
- #include <AP_AHRS/AP_AHRS.h>
- #ifndef AP_MODULE_DEFAULT_DIRECTORY
- #define AP_MODULE_DEFAULT_DIRECTORY "/usr/lib/ardupilot/modules"
- #endif
- class AP_Module {
- public:
-
- static void init(const char *module_path);
-
-
- static void call_hook_setup_start(void);
-
- static void call_hook_setup_complete(void);
-
-
- static void call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs);
-
- static void call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f &gyro);
-
- static void call_hook_accel_sample(uint8_t instance, float dt, const Vector3f &accel, bool fsync_set);
-
-
- private:
- enum ModuleHooks {
- HOOK_SETUP_START = 0,
- HOOK_SETUP_COMPLETE,
- HOOK_AHRS_UPDATE,
- HOOK_GYRO_SAMPLE,
- HOOK_ACCEL_SAMPLE,
- NUM_HOOKS
- };
-
- struct hook_list {
- struct hook_list *next;
- void *symbol;
- };
-
- static struct hook_list *hooks[NUM_HOOKS];
-
-
-
- static const char *hook_names[NUM_HOOKS];
-
-
- static void module_scan(const char *path);
- };
- #endif
|