From a5ccb1d3128d59abffa4312a4731ab454938f093 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH] AP_Landing: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Landing/AP_Landing.cpp | 2 ++ libraries/AP_Landing/AP_Landing_Deepstall.cpp | 2 ++ libraries/AP_Landing/AP_Landing_Slope.cpp | 2 ++ 3 files changed, 6 insertions(+) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 211ecdd46f..ca396805cf 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -625,6 +625,7 @@ bool AP_Landing::is_complete(void) const void AP_Landing::Log(void) const { +#if HAL_LOGGING_ENABLED switch (type) { case TYPE_STANDARD_GLIDE_SLOPE: type_slope_log(); @@ -637,6 +638,7 @@ void AP_Landing::Log(void) const default: break; } +#endif } /* diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index 0a690acbeb..e465b869de 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -456,6 +456,7 @@ const AP_PIDInfo& AP_Landing_Deepstall::get_pid_info(void) const return ds_PID.get_pid_info(); } +#if HAL_LOGGING_ENABLED void AP_Landing_Deepstall::Log(void) const { const AP_PIDInfo& pid_info = ds_PID.get_pid_info(); struct log_DSTL pkt = { @@ -479,6 +480,7 @@ void AP_Landing_Deepstall::Log(void) const { }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // termination handling, expected to set the servo outputs bool AP_Landing_Deepstall::terminate(void) { diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 4ec0c7cfa7..7b4182e0af 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -407,6 +407,7 @@ bool AP_Landing::type_slope_is_complete(void) const return (type_slope_stage == SlopeStage::FINAL); } +#if HAL_LOGGING_ENABLED void AP_Landing::type_slope_log(void) const { // @LoggerMessage: LAND @@ -429,6 +430,7 @@ void AP_Landing::type_slope_log(void) const (double)alt_offset, (double)height_flare_log); } +#endif bool AP_Landing::type_slope_is_throttle_suppressed(void) const {