mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 07:38:28 -04:00
AP_Module: use ifdef in function, not caller
suggestion by Lucas
This commit is contained in:
parent
eee9fc88a1
commit
7d48b25207
@ -102,11 +102,13 @@ void AP_Module::init(const char *module_path)
|
|||||||
*/
|
*/
|
||||||
void AP_Module::call_hook_setup_start(void)
|
void AP_Module::call_hook_setup_start(void)
|
||||||
{
|
{
|
||||||
|
#if AP_MODULE_SUPPORTED
|
||||||
uint64_t now = AP_HAL::micros64();
|
uint64_t now = AP_HAL::micros64();
|
||||||
for (const struct hook_list *h=hooks[HOOK_SETUP_START]; h; h=h->next) {
|
for (const struct hook_list *h=hooks[HOOK_SETUP_START]; h; h=h->next) {
|
||||||
ap_hook_setup_start_fn_t fn = reinterpret_cast<ap_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);
|
fn(now);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -114,11 +116,13 @@ void AP_Module::call_hook_setup_start(void)
|
|||||||
*/
|
*/
|
||||||
void AP_Module::call_hook_setup_complete(void)
|
void AP_Module::call_hook_setup_complete(void)
|
||||||
{
|
{
|
||||||
|
#if AP_MODULE_SUPPORTED
|
||||||
uint64_t now = AP_HAL::micros64();
|
uint64_t now = AP_HAL::micros64();
|
||||||
for (const struct hook_list *h=hooks[HOOK_SETUP_COMPLETE]; h; h=h->next) {
|
for (const struct hook_list *h=hooks[HOOK_SETUP_COMPLETE]; h; h=h->next) {
|
||||||
ap_hook_setup_complete_fn_t fn = reinterpret_cast<ap_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);
|
fn(now);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -126,6 +130,7 @@ void AP_Module::call_hook_setup_complete(void)
|
|||||||
*/
|
*/
|
||||||
void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
|
void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
|
||||||
{
|
{
|
||||||
|
#if AP_MODULE_SUPPORTED
|
||||||
if (hooks[HOOK_AHRS_UPDATE] == nullptr) {
|
if (hooks[HOOK_AHRS_UPDATE] == nullptr) {
|
||||||
// avoid filling in AHRS_state
|
// avoid filling in AHRS_state
|
||||||
return;
|
return;
|
||||||
@ -193,6 +198,7 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
|
|||||||
ap_hook_AHRS_update_fn_t fn = reinterpret_cast<ap_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);
|
fn(&state);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -201,6 +207,7 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS_NavEKF &ahrs)
|
|||||||
*/
|
*/
|
||||||
void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f &gyro)
|
void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f &gyro)
|
||||||
{
|
{
|
||||||
|
#if AP_MODULE_SUPPORTED
|
||||||
if (hooks[HOOK_GYRO_SAMPLE] == nullptr) {
|
if (hooks[HOOK_GYRO_SAMPLE] == nullptr) {
|
||||||
// avoid filling in struct
|
// avoid filling in struct
|
||||||
return;
|
return;
|
||||||
@ -222,6 +229,7 @@ void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f
|
|||||||
ap_hook_gyro_sample_fn_t fn = reinterpret_cast<ap_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);
|
fn(&state);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -229,6 +237,7 @@ void AP_Module::call_hook_gyro_sample(uint8_t instance, float dt, const Vector3f
|
|||||||
*/
|
*/
|
||||||
void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3f &accel)
|
void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3f &accel)
|
||||||
{
|
{
|
||||||
|
#if AP_MODULE_SUPPORTED
|
||||||
if (hooks[HOOK_ACCEL_SAMPLE] == nullptr) {
|
if (hooks[HOOK_ACCEL_SAMPLE] == nullptr) {
|
||||||
// avoid filling in struct
|
// avoid filling in struct
|
||||||
return;
|
return;
|
||||||
@ -250,4 +259,5 @@ void AP_Module::call_hook_accel_sample(uint8_t instance, float dt, const Vector3
|
|||||||
ap_hook_accel_sample_fn_t fn = reinterpret_cast<ap_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);
|
fn(&state);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user