AP_Winch: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:09 +10:00 committed by Andrew Tridgell
parent 9de01998c3
commit 8801b78a9c
7 changed files with 17 additions and 0 deletions

View File

@ -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

View File

@ -23,6 +23,7 @@
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AC_PID/AC_PID.h>
#include <AP_Logger/AP_Logger_config.h>
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;

View File

@ -19,6 +19,8 @@
#if AP_WINCH_ENABLED
#include <AP_Logger/AP_Logger_config.h>
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 {

View File

@ -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()

View File

@ -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:

View File

@ -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

View File

@ -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: