From f930c38712b045cd7fb419ac37e689cf76102315 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH] APM_Control: allow compilation with HAL_LOGGING_ENABLED false --- libraries/APM_Control/AP_AutoTune.cpp | 2 ++ libraries/APM_Control/AR_PosControl.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 87c84ee94a..d93dbb0d3a 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -247,6 +247,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) const uint32_t now = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED if (now - last_log_ms >= 40) { // log at 25Hz struct log_ATRP pkt = { @@ -269,6 +270,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) AP::logger().WriteBlock(&pkt, sizeof(pkt)); last_log_ms = now; } +#endif if (new_state == state) { if (state == ATState::IDLE && diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 4107082558..112c508934 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -363,6 +363,7 @@ void AR_PosControl::get_srate(float &velocity_srate) velocity_srate = _pid_vel.get_pid_info_x().slew_rate; } +#if HAL_LOGGING_ENABLED // write PSC logs void AR_PosControl::write_log() { @@ -401,6 +402,7 @@ void AR_PosControl::write_log() _accel_target.y * 100.0, // target accel curr_accel_NED.y); // accel } +#endif /// initialise ekf xy position reset check void AR_PosControl::init_ekf_xy_reset()