Browse Source

AP_Module: changed hook prefix to ap_hook_

master
Andrew Tridgell 9 years ago
parent
commit
5ce472ab8a
  1. 20
      libraries/AP_Module/AP_Module.cpp
  2. 20
      libraries/AP_Module/AP_Module_Structures.h
  3. 10
      libraries/AP_Module/examples/ModuleTest/module/moduletest.c

20
libraries/AP_Module/AP_Module.cpp

@ -29,11 +29,11 @@ @@ -29,11 +29,11 @@
struct AP_Module::hook_list *AP_Module::hooks[NUM_HOOKS];
const char *AP_Module::hook_names[AP_Module::NUM_HOOKS] = {
"hook_setup_start",
"hook_setup_complete",
"hook_AHRS_update",
"hook_gyro_sample",
"hook_accel_sample",
"ap_hook_setup_start",
"ap_hook_setup_complete",
"ap_hook_AHRS_update",
"ap_hook_gyro_sample",
"ap_hook_accel_sample",
};
/*
@ -104,7 +104,7 @@ void AP_Module::call_hook_setup_start(void) @@ -104,7 +104,7 @@ void AP_Module::call_hook_setup_start(void)
{
uint64_t now = AP_HAL::micros64();
for (const struct hook_list *h=hooks[HOOK_SETUP_START]; h; h=h->next) {
hook_setup_start_fn_t fn = reinterpret_cast<hook_setup_start_fn_t>(h->symbol);
ap_hook_setup_start_fn_t fn = reinterpret_cast<ap_hook_setup_start_fn_t>(h->symbol);
fn(now);
}
}
@ -116,7 +116,7 @@ void AP_Module::call_hook_setup_complete(void) @@ -116,7 +116,7 @@ void AP_Module::call_hook_setup_complete(void)
{
uint64_t now = AP_HAL::micros64();
for (const struct hook_list *h=hooks[HOOK_SETUP_COMPLETE]; h; h=h->next) {
hook_setup_complete_fn_t fn = reinterpret_cast<hook_setup_complete_fn_t>(h->symbol);
ap_hook_setup_complete_fn_t fn = reinterpret_cast<ap_hook_setup_complete_fn_t>(h->symbol);
fn(now);
}
}
@ -190,7 +190,7 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs) @@ -190,7 +190,7 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
state.accel_ef[2] = accel_ef[0];
for (const struct hook_list *h=hooks[HOOK_AHRS_UPDATE]; h; h=h->next) {
hook_AHRS_update_fn_t fn = reinterpret_cast<hook_AHRS_update_fn_t>(h->symbol);
ap_hook_AHRS_update_fn_t fn = reinterpret_cast<ap_hook_AHRS_update_fn_t>(h->symbol);
fn(&state);
}
}
@ -219,7 +219,7 @@ void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f @@ -219,7 +219,7 @@ void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f
state.gyro[2] = gyro[2];
for (const struct hook_list *h=hooks[HOOK_GYRO_SAMPLE]; h; h=h->next) {
hook_gyro_sample_fn_t fn = reinterpret_cast<hook_gyro_sample_fn_t>(h->symbol);
ap_hook_gyro_sample_fn_t fn = reinterpret_cast<ap_hook_gyro_sample_fn_t>(h->symbol);
fn(&state);
}
}
@ -247,7 +247,7 @@ void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3 @@ -247,7 +247,7 @@ void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3
state.accel[2] = accel[2];
for (const struct hook_list *h=hooks[HOOK_ACCEL_SAMPLE]; h; h=h->next) {
hook_accel_sample_fn_t fn = reinterpret_cast<hook_accel_sample_fn_t>(h->symbol);
ap_hook_accel_sample_fn_t fn = reinterpret_cast<ap_hook_accel_sample_fn_t>(h->symbol);
fn(&state);
}
}

20
libraries/AP_Module/AP_Module_Structures.h

@ -127,20 +127,20 @@ struct accel_sample { @@ -127,20 +127,20 @@ struct accel_sample {
/*
prototypes for hook functions
*/
typedef void (*hook_setup_start_fn_t)(uint64_t);
void hook_setup_start(uint64_t time_us);
typedef void (*ap_hook_setup_start_fn_t)(uint64_t);
void ap_hook_setup_start(uint64_t time_us);
typedef void (*hook_setup_complete_fn_t)(uint64_t);
void hook_setup_complete(uint64_t time_us);
typedef void (*ap_hook_setup_complete_fn_t)(uint64_t);
void ap_hook_setup_complete(uint64_t time_us);
typedef void (*hook_AHRS_update_fn_t)(const struct AHRS_state *);
void hook_AHRS_update(const struct AHRS_state *state);
typedef void (*ap_hook_AHRS_update_fn_t)(const struct AHRS_state *);
void ap_hook_AHRS_update(const struct AHRS_state *state);
typedef void (*hook_gyro_sample_fn_t)(const struct gyro_sample *);
void hook_gyro_sample(const struct gyro_sample *state);
typedef void (*ap_hook_gyro_sample_fn_t)(const struct gyro_sample *);
void ap_hook_gyro_sample(const struct gyro_sample *state);
typedef void (*hook_accel_sample_fn_t)(const struct accel_sample *);
void hook_accel_sample(const struct accel_sample *state);
typedef void (*ap_hook_accel_sample_fn_t)(const struct accel_sample *);
void ap_hook_accel_sample(const struct accel_sample *state);
#ifdef __cplusplus
}

10
libraries/AP_Module/examples/ModuleTest/module/moduletest.c

@ -9,12 +9,12 @@ @@ -9,12 +9,12 @@
#include <AP_Module_Structures.h>
void hook_setup_start(uint64_t time_us)
void ap_hook_setup_start(uint64_t time_us)
{
printf("setup_start called\n");
}
void hook_setup_complete(uint64_t time_us)
void ap_hook_setup_complete(uint64_t time_us)
{
printf("setup_complete called\n");
}
@ -22,7 +22,7 @@ void hook_setup_complete(uint64_t time_us) @@ -22,7 +22,7 @@ void hook_setup_complete(uint64_t time_us)
#define degrees(x) (x * 180.0 / M_PI)
void hook_AHRS_update(const struct AHRS_state *state)
void ap_hook_AHRS_update(const struct AHRS_state *state)
{
static uint64_t last_print_us;
if (state->time_us - last_print_us < 1000000UL) {
@ -36,7 +36,7 @@ void hook_AHRS_update(const struct AHRS_state *state) @@ -36,7 +36,7 @@ void hook_AHRS_update(const struct AHRS_state *state)
degrees(state->eulers[2]));
}
void hook_gyro_sample(const struct gyro_sample *state)
void ap_hook_gyro_sample(const struct gyro_sample *state)
{
static uint64_t last_print_us;
if (state->time_us - last_print_us < 1000000UL) {
@ -50,7 +50,7 @@ void hook_gyro_sample(const struct gyro_sample *state) @@ -50,7 +50,7 @@ void hook_gyro_sample(const struct gyro_sample *state)
degrees(state->gyro[2]));
}
void hook_accel_sample(const struct accel_sample *state)
void ap_hook_accel_sample(const struct accel_sample *state)
{
static uint64_t last_print_us;
if (state->time_us - last_print_us < 1000000UL) {

Loading…
Cancel
Save