diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index 4a3a41db40..5738fdfea9 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -159,7 +159,9 @@ bool AP_Winch::pre_arm_check(char *failmsg, uint8_t failmsg_len) const } PASS_TO_BACKEND(update) +#if HAL_LOGGING_ENABLED PASS_TO_BACKEND(write_log) +#endif #undef PASS_TO_BACKEND diff --git a/libraries/AP_Winch/AP_Winch.h b/libraries/AP_Winch/AP_Winch.h index df1ecf9c89..8a3b0f72a8 100644 --- a/libraries/AP_Winch/AP_Winch.h +++ b/libraries/AP_Winch/AP_Winch.h @@ -23,6 +23,7 @@ #include #include #include +#include class AP_Winch_Backend; @@ -64,8 +65,10 @@ public: // send status to ground station void send_status(const class GCS_MAVLINK &channel); +#if HAL_LOGGING_ENABLED // write log void write_log(); +#endif // returns true if pre arm checks have passed bool pre_arm_check(char *failmsg, uint8_t failmsg_len) const; diff --git a/libraries/AP_Winch/AP_Winch_Backend.h b/libraries/AP_Winch/AP_Winch_Backend.h index 0504a753db..d03adde345 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.h +++ b/libraries/AP_Winch/AP_Winch_Backend.h @@ -19,6 +19,8 @@ #if AP_WINCH_ENABLED +#include + class AP_Winch_Backend { public: AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) : @@ -39,8 +41,10 @@ public: // send status to ground station virtual void send_status(const GCS_MAVLINK &channel) = 0; +#if HAL_LOGGING_ENABLED // write log virtual void write_log() = 0; +#endif // helper to check if option enabled bool option_enabled(AP_Winch::Options option) const { diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index d80a8f5876..88f6184472 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -86,6 +86,7 @@ void AP_Winch_Daiwa::send_status(const GCS_MAVLINK &channel) status_bitmask); } +#if HAL_LOGGING_ENABLED // write log void AP_Winch_Daiwa::write_log() { @@ -102,6 +103,7 @@ void AP_Winch_Daiwa::write_log() latest.voltage, constrain_int16(latest.motor_temp, INT8_MIN, INT8_MAX)); } +#endif // read incoming data from winch and update intermediate and latest structures void AP_Winch_Daiwa::read_data_from_winch() diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.h b/libraries/AP_Winch/AP_Winch_Daiwa.h index 301a73d9e9..a49eb9e58f 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.h +++ b/libraries/AP_Winch/AP_Winch_Daiwa.h @@ -52,8 +52,10 @@ public: // send status to ground station void send_status(const GCS_MAVLINK &channel) override; +#if HAL_LOGGING_ENABLED // write log void write_log() override; +#endif private: diff --git a/libraries/AP_Winch/AP_Winch_PWM.cpp b/libraries/AP_Winch/AP_Winch_PWM.cpp index ba8d89a8c4..7607cd97e2 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.cpp +++ b/libraries/AP_Winch/AP_Winch_PWM.cpp @@ -93,6 +93,7 @@ void AP_Winch_PWM::send_status(const GCS_MAVLINK &channel) } // write log +#if HAL_LOGGING_ENABLED void AP_Winch_PWM::write_log() { AP::logger().Write_Winch( @@ -108,5 +109,6 @@ void AP_Winch_PWM::write_log() 0, // voltage (unsupported) 0); // temp (unsupported) } +#endif #endif // AP_WINCH_PWM_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_PWM.h b/libraries/AP_Winch/AP_Winch_PWM.h index 58ef71f3c6..9fd6ff2eda 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.h +++ b/libraries/AP_Winch/AP_Winch_PWM.h @@ -36,8 +36,10 @@ public: // send status to ground station void send_status(const GCS_MAVLINK &channel) override; +#if HAL_LOGGING_ENABLED // write log void write_log() override; +#endif private: