From 8ccd0ccd3ac3fd823d10d88f008598c3688ada88 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Mar 2023 11:48:38 +1100 Subject: [PATCH] AP_Winch: add and use AP_WINCH_ENABLED --- libraries/AP_Winch/AP_Winch.cpp | 5 +++++ libraries/AP_Winch/AP_Winch.h | 6 ++++++ libraries/AP_Winch/AP_Winch_Backend.cpp | 4 ++++ libraries/AP_Winch/AP_Winch_Backend.h | 4 ++++ libraries/AP_Winch/AP_Winch_Daiwa.cpp | 4 ++++ libraries/AP_Winch/AP_Winch_Daiwa.h | 4 ++++ libraries/AP_Winch/AP_Winch_PWM.cpp | 4 ++++ libraries/AP_Winch/AP_Winch_PWM.h | 4 ++++ libraries/AP_Winch/AP_Winch_config.h | 19 +++++++++++++++++++ 9 files changed, 54 insertions(+) create mode 100644 libraries/AP_Winch/AP_Winch_config.h diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index b89519cb0c..deb769f733 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -1,4 +1,7 @@ #include "AP_Winch.h" + +#if AP_WINCH_ENABLED + #include "AP_Winch_PWM.h" #include "AP_Winch_Daiwa.h" @@ -157,3 +160,5 @@ AP_Winch *winch() } }; + +#endif // AP_WINCH_ENABLED diff --git a/libraries/AP_Winch/AP_Winch.h b/libraries/AP_Winch/AP_Winch.h index c48a23a815..0536932327 100644 --- a/libraries/AP_Winch/AP_Winch.h +++ b/libraries/AP_Winch/AP_Winch.h @@ -15,6 +15,10 @@ #pragma once +#include "AP_Winch_config.h" + +#if AP_WINCH_ENABLED + #include #include #include @@ -103,3 +107,5 @@ private: namespace AP { AP_Winch *winch(); }; + +#endif // AP_WINCH_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_Backend.cpp b/libraries/AP_Winch/AP_Winch_Backend.cpp index 61e395de01..438b1a7b58 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.cpp +++ b/libraries/AP_Winch/AP_Winch_Backend.cpp @@ -1,5 +1,7 @@ #include +#if AP_WINCH_ENABLED + #include #include @@ -67,3 +69,5 @@ float AP_Winch_Backend::get_rate_limited_by_accel(float rate, float dt) return rate_limited; } + +#endif // AP_WINCH_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_Backend.h b/libraries/AP_Winch/AP_Winch_Backend.h index fe84d4b3b8..ef749a11f6 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.h +++ b/libraries/AP_Winch/AP_Winch_Backend.h @@ -17,6 +17,8 @@ #include +#if AP_WINCH_ENABLED + class AP_Winch_Backend { public: AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) : @@ -58,3 +60,5 @@ protected: int16_t previous_radio_in = -1; // previous RC input from pilot, used to ignore small changes float previous_rate; // previous rate used for acceleration limiting }; + +#endif // AP_WINCH_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index c9373e9b63..df1ce04484 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -1,5 +1,7 @@ #include +#if AP_WINCH_DAIWA_ENABLED + #include #include #include @@ -223,3 +225,5 @@ void AP_Winch_Daiwa::control_winch() } SRV_Channels::set_output_scaled(SRV_Channel::k_winch, scaled_output); } + +#endif // AP_WINCH_DAIWA_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.h b/libraries/AP_Winch/AP_Winch_Daiwa.h index 8b11af5c62..61b9dc630b 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.h +++ b/libraries/AP_Winch/AP_Winch_Daiwa.h @@ -30,6 +30,8 @@ #include +#if AP_WINCH_DAIWA_ENABLED + class AP_Winch_Daiwa : public AP_Winch_Backend { public: @@ -105,3 +107,5 @@ private: WAITING_FOR_MOTOR_TEMP } parse_state; }; + +#endif // AP_WINCH_DAIWA_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_PWM.cpp b/libraries/AP_Winch/AP_Winch_PWM.cpp index b261c59b27..ba8d89a8c4 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.cpp +++ b/libraries/AP_Winch/AP_Winch_PWM.cpp @@ -1,5 +1,7 @@ #include "AP_Winch_PWM.h" +#if AP_WINCH_PWM_ENABLED + #include #include #include @@ -106,3 +108,5 @@ void AP_Winch_PWM::write_log() 0, // voltage (unsupported) 0); // temp (unsupported) } + +#endif // AP_WINCH_PWM_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_PWM.h b/libraries/AP_Winch/AP_Winch_PWM.h index 4c4976c233..58ef71f3c6 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.h +++ b/libraries/AP_Winch/AP_Winch_PWM.h @@ -17,6 +17,8 @@ #include +#if AP_WINCH_PWM_ENABLED + class AP_Winch_PWM : public AP_Winch_Backend { public: @@ -45,3 +47,5 @@ private: uint32_t control_update_ms; // last time control_winch was called float line_length; // estimated length of line in meters }; + +#endif // AP_WINCH_PWM_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_config.h b/libraries/AP_Winch/AP_Winch_config.h new file mode 100644 index 0000000000..0cd33754df --- /dev/null +++ b/libraries/AP_Winch/AP_Winch_config.h @@ -0,0 +1,19 @@ +#pragma once + +#include + +#ifndef AP_WINCH_ENABLED +#define AP_WINCH_ENABLED 1 +#endif + +#ifndef AP_WINCH_BACKEND_DEFAULT_ENABLED +#define AP_WINCH_BACKEND_DEFAULT_ENABLED AP_WINCH_ENABLED +#endif + +#ifndef AP_WINCH_DAIWA_ENABLED +#define AP_WINCH_DAIWA_ENABLED AP_WINCH_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_WINCH_PWM_ENABLED +#define AP_WINCH_PWM_ENABLED AP_WINCH_BACKEND_DEFAULT_ENABLED +#endif