mirror of https://github.com/ArduPilot/ardupilot
AP_Winch: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
9de01998c3
commit
8801b78a9c
|
@ -159,7 +159,9 @@ bool AP_Winch::pre_arm_check(char *failmsg, uint8_t failmsg_len) const
|
||||||
}
|
}
|
||||||
|
|
||||||
PASS_TO_BACKEND(update)
|
PASS_TO_BACKEND(update)
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
PASS_TO_BACKEND(write_log)
|
PASS_TO_BACKEND(write_log)
|
||||||
|
#endif
|
||||||
|
|
||||||
#undef PASS_TO_BACKEND
|
#undef PASS_TO_BACKEND
|
||||||
|
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AC_PID/AC_PID.h>
|
#include <AC_PID/AC_PID.h>
|
||||||
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
class AP_Winch_Backend;
|
class AP_Winch_Backend;
|
||||||
|
|
||||||
|
@ -64,8 +65,10 @@ public:
|
||||||
// send status to ground station
|
// send status to ground station
|
||||||
void send_status(const class GCS_MAVLINK &channel);
|
void send_status(const class GCS_MAVLINK &channel);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write log
|
// write log
|
||||||
void write_log();
|
void write_log();
|
||||||
|
#endif
|
||||||
|
|
||||||
// returns true if pre arm checks have passed
|
// returns true if pre arm checks have passed
|
||||||
bool pre_arm_check(char *failmsg, uint8_t failmsg_len) const;
|
bool pre_arm_check(char *failmsg, uint8_t failmsg_len) const;
|
||||||
|
|
|
@ -19,6 +19,8 @@
|
||||||
|
|
||||||
#if AP_WINCH_ENABLED
|
#if AP_WINCH_ENABLED
|
||||||
|
|
||||||
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
class AP_Winch_Backend {
|
class AP_Winch_Backend {
|
||||||
public:
|
public:
|
||||||
AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) :
|
AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) :
|
||||||
|
@ -39,8 +41,10 @@ public:
|
||||||
// send status to ground station
|
// send status to ground station
|
||||||
virtual void send_status(const GCS_MAVLINK &channel) = 0;
|
virtual void send_status(const GCS_MAVLINK &channel) = 0;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write log
|
// write log
|
||||||
virtual void write_log() = 0;
|
virtual void write_log() = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
// helper to check if option enabled
|
// helper to check if option enabled
|
||||||
bool option_enabled(AP_Winch::Options option) const {
|
bool option_enabled(AP_Winch::Options option) const {
|
||||||
|
|
|
@ -86,6 +86,7 @@ void AP_Winch_Daiwa::send_status(const GCS_MAVLINK &channel)
|
||||||
status_bitmask);
|
status_bitmask);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write log
|
// write log
|
||||||
void AP_Winch_Daiwa::write_log()
|
void AP_Winch_Daiwa::write_log()
|
||||||
{
|
{
|
||||||
|
@ -102,6 +103,7 @@ void AP_Winch_Daiwa::write_log()
|
||||||
latest.voltage,
|
latest.voltage,
|
||||||
constrain_int16(latest.motor_temp, INT8_MIN, INT8_MAX));
|
constrain_int16(latest.motor_temp, INT8_MIN, INT8_MAX));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// read incoming data from winch and update intermediate and latest structures
|
// read incoming data from winch and update intermediate and latest structures
|
||||||
void AP_Winch_Daiwa::read_data_from_winch()
|
void AP_Winch_Daiwa::read_data_from_winch()
|
||||||
|
|
|
@ -52,8 +52,10 @@ public:
|
||||||
// send status to ground station
|
// send status to ground station
|
||||||
void send_status(const GCS_MAVLINK &channel) override;
|
void send_status(const GCS_MAVLINK &channel) override;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write log
|
// write log
|
||||||
void write_log() override;
|
void write_log() override;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
|
|
@ -93,6 +93,7 @@ void AP_Winch_PWM::send_status(const GCS_MAVLINK &channel)
|
||||||
}
|
}
|
||||||
|
|
||||||
// write log
|
// write log
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_Winch_PWM::write_log()
|
void AP_Winch_PWM::write_log()
|
||||||
{
|
{
|
||||||
AP::logger().Write_Winch(
|
AP::logger().Write_Winch(
|
||||||
|
@ -108,5 +109,6 @@ void AP_Winch_PWM::write_log()
|
||||||
0, // voltage (unsupported)
|
0, // voltage (unsupported)
|
||||||
0); // temp (unsupported)
|
0); // temp (unsupported)
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // AP_WINCH_PWM_ENABLED
|
#endif // AP_WINCH_PWM_ENABLED
|
||||||
|
|
|
@ -36,8 +36,10 @@ public:
|
||||||
// send status to ground station
|
// send status to ground station
|
||||||
void send_status(const GCS_MAVLINK &channel) override;
|
void send_status(const GCS_MAVLINK &channel) override;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write log
|
// write log
|
||||||
void write_log() override;
|
void write_log() override;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue