AP_Notify: add defines for some AP_Notify LED libraries

allow ProfiLEDs (serial and SPI) and NeoPixel to be compiled out
This commit is contained in:
Peter Barker 2023-03-01 13:57:09 +11:00 committed by Andrew Tridgell
parent a647f79371
commit d9aa0c9cf0
9 changed files with 73 additions and 6 deletions

View File

@ -325,15 +325,21 @@ void AP_Notify::add_backends(void)
ADD_BACKEND(new PCA9685LED_I2C()); ADD_BACKEND(new PCA9685LED_I2C());
break; break;
#endif #endif
#if AP_NOTIFY_NEOPIXEL_ENABLED
case Notify_LED_NeoPixel: case Notify_LED_NeoPixel:
ADD_BACKEND(new NeoPixel()); ADD_BACKEND(new NeoPixel());
break; break;
#endif
#if AP_NOTIFY_PROFILED_ENABLED
case Notify_LED_ProfiLED: case Notify_LED_ProfiLED:
ADD_BACKEND(new ProfiLED()); ADD_BACKEND(new ProfiLED());
break; break;
#endif
#if AP_NOTIFY_PROFILED_SPI_ENABLED
case Notify_LED_ProfiLED_SPI: case Notify_LED_ProfiLED_SPI:
ADD_BACKEND(new ProfiLED_SPI()); ADD_BACKEND(new ProfiLED_SPI());
break; break;
#endif
case Notify_LED_OreoLED: case Notify_LED_OreoLED:
#if AP_NOTIFY_OREOLED_ENABLED #if AP_NOTIFY_OREOLED_ENABLED
if (_oreo_theme) { if (_oreo_theme) {

View File

@ -74,8 +74,12 @@ public:
Notify_LED_NCP5623_I2C_External = (1 << 6), // External NCP5623 Notify_LED_NCP5623_I2C_External = (1 << 6), // External NCP5623
Notify_LED_NCP5623_I2C_Internal = (1 << 7), // Internal NCP5623 Notify_LED_NCP5623_I2C_Internal = (1 << 7), // Internal NCP5623
#endif #endif
#if AP_NOTIFY_NEOPIXEL_ENABLED
Notify_LED_NeoPixel = (1 << 8), // NeoPixel 5050 AdaFruit 1655 SK6812 Worldsemi WS2812B Notify_LED_NeoPixel = (1 << 8), // NeoPixel 5050 AdaFruit 1655 SK6812 Worldsemi WS2812B
#endif
#if AP_NOTIFY_PROFILED_ENABLED
Notify_LED_ProfiLED = (1 << 9), // ProfiLED Notify_LED_ProfiLED = (1 << 9), // ProfiLED
#endif
Notify_LED_Scripting = (1 << 10),// Colour accessor for scripting Notify_LED_Scripting = (1 << 10),// Colour accessor for scripting
Notify_LED_DShot = (1 << 11),// Use dshot commands to set ESC LEDs Notify_LED_DShot = (1 << 11),// Use dshot commands to set ESC LEDs
Notify_LED_ProfiLED_SPI = (1 << 12), // ProfiLED Notify_LED_ProfiLED_SPI = (1 << 12), // ProfiLED

View File

@ -4,6 +4,7 @@
#if HAL_GCS_ENABLED #if HAL_GCS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#endif #endif
#include <AP_SerialLED/AP_SerialLED_config.h>
#ifndef AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED #ifndef AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
#define AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED HAL_GCS_ENABLED #define AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED HAL_GCS_ENABLED
@ -21,6 +22,14 @@
#define AP_NOTIFY_PCA9685_ENABLED 1 #define AP_NOTIFY_PCA9685_ENABLED 1
#endif #endif
#ifndef AP_NOTIFY_PROFILED_SPI_ENABLED
#define AP_NOTIFY_PROFILED_SPI_ENABLED 1
#endif
#ifndef AP_NOTIFY_SERIALLED_ENABLED
#define AP_NOTIFY_SERIALLED_ENABLED AP_SERIALLED_ENABLED
#endif
#ifndef AP_NOTIFY_TOSHIBALED_ENABLED #ifndef AP_NOTIFY_TOSHIBALED_ENABLED
#define AP_NOTIFY_TOSHIBALED_ENABLED 1 #define AP_NOTIFY_TOSHIBALED_ENABLED 1
#endif #endif
@ -28,3 +37,12 @@
#ifndef AP_NOTIFY_OREOLED_ENABLED #ifndef AP_NOTIFY_OREOLED_ENABLED
#define AP_NOTIFY_OREOLED_ENABLED 0 #define AP_NOTIFY_OREOLED_ENABLED 0
#endif #endif
// Serial LED backends:
#ifndef AP_NOTIFY_PROFILED_ENABLED
#define AP_NOTIFY_PROFILED_ENABLED AP_NOTIFY_SERIALLED_ENABLED
#endif
#ifndef AP_NOTIFY_NEOPIXEL_ENABLED
#define AP_NOTIFY_NEOPIXEL_ENABLED AP_NOTIFY_SERIALLED_ENABLED
#endif

View File

@ -13,8 +13,11 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Notify/AP_Notify.h"
#include "NeoPixel.h" #include "NeoPixel.h"
#if AP_NOTIFY_NEOPIXEL_ENABLED
#include "AP_Notify/AP_Notify.h"
#include "SRV_Channel/SRV_Channel.h" #include "SRV_Channel/SRV_Channel.h"
// This limit is from the dshot driver rcout groups limit // This limit is from the dshot driver rcout groups limit
@ -64,3 +67,5 @@ uint16_t NeoPixel::init_ports()
return mask; return mask;
} }
#endif // AP_NOTIFY_NEOPIXEL_ENABLED

View File

@ -14,6 +14,10 @@
*/ */
#pragma once #pragma once
#include "AP_Notify_config.h"
#if AP_NOTIFY_NEOPIXEL_ENABLED
#include "RGBLed.h" #include "RGBLed.h"
#include "SerialLED.h" #include "SerialLED.h"
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
@ -24,3 +28,5 @@ public:
uint16_t init_ports() override; uint16_t init_ports() override;
}; };
#endif // AP_NOTIFY_NEOPIXEL_ENABLED

View File

@ -13,8 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Notify/AP_Notify.h"
#include "ProfiLED.h" #include "ProfiLED.h"
#include "AP_Notify/AP_Notify.h"
#include "SRV_Channel/SRV_Channel.h" #include "SRV_Channel/SRV_Channel.h"
#include <utility> #include <utility>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
@ -29,6 +31,8 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#if AP_NOTIFY_PROFILED_ENABLED
ProfiLED::ProfiLED() : ProfiLED::ProfiLED() :
SerialLED(ProfiLED_OFF, ProfiLED_HIGH, ProfiLED_MEDIUM, ProfiLED_LOW) SerialLED(ProfiLED_OFF, ProfiLED_HIGH, ProfiLED_MEDIUM, ProfiLED_LOW)
{ {
@ -62,7 +66,9 @@ uint16_t ProfiLED::init_ports()
return mask; return mask;
} }
#endif // AP_NOTIFY_PROFILED_ENABLED
#if AP_NOTIFY_PROFILED_SPI_ENABLED
ProfiLED_SPI::ProfiLED_SPI() : ProfiLED_SPI::ProfiLED_SPI() :
RGBLed(ProfiLED_OFF, ProfiLED_HIGH, ProfiLED_MEDIUM, ProfiLED_LOW) {} RGBLed(ProfiLED_OFF, ProfiLED_HIGH, ProfiLED_MEDIUM, ProfiLED_LOW) {}
@ -161,3 +167,5 @@ void ProfiLED_SPI::update_led_strip() {
send_buf_len = 0; send_buf_len = 0;
} }
} }
#endif // AP_NOTIFY_PROFILED_SPI_ENABLED

View File

@ -14,10 +14,13 @@
*/ */
#pragma once #pragma once
#include "RGBLed.h" #include "AP_Notify_config.h"
#include "SerialLED.h"
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#if AP_NOTIFY_PROFILED_ENABLED
#include "SerialLED.h"
class ProfiLED: public SerialLED { class ProfiLED: public SerialLED {
public: public:
ProfiLED(); ProfiLED();
@ -25,6 +28,11 @@ public:
uint16_t init_ports() override; uint16_t init_ports() override;
}; };
#endif // AP_NOTIFY_PROFILED_ENABLED
#if AP_NOTIFY_PROFILED_SPI_ENABLED
#include <AP_HAL/SPIDevice.h>
#include "RGBLed.h"
class ProfiLED_SPI: public RGBLed { class ProfiLED_SPI: public RGBLed {
public: public:
@ -53,3 +61,6 @@ private:
uint32_t _last_init_ms; uint32_t _last_init_ms;
void update_led_strip(); void update_led_strip();
}; };
#endif // AP_NOTIFY_PROFILED_SPI_ENABLED

View File

@ -13,9 +13,10 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_Notify/AP_Notify.h"
#include "SerialLED.h" #include "SerialLED.h"
#if AP_NOTIFY_SERIALLED_ENABLED
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
SerialLED::SerialLED(uint8_t led_off, uint8_t led_bright, uint8_t led_medium, uint8_t led_dim) : SerialLED::SerialLED(uint8_t led_off, uint8_t led_bright, uint8_t led_medium, uint8_t led_dim) :
@ -55,3 +56,5 @@ bool SerialLED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue)
return true; return true;
} }
#endif // AP_NOTIFY_SERIALLED_ENABLED

View File

@ -14,6 +14,10 @@
*/ */
#pragma once #pragma once
#include "AP_Notify_config.h"
#if AP_NOTIFY_SERIALLED_ENABLED
#include "RGBLed.h" #include "RGBLed.h"
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_SerialLED/AP_SerialLED.h> #include <AP_SerialLED/AP_SerialLED.h>
@ -41,3 +45,5 @@ private:
HAL_Semaphore _sem; HAL_Semaphore _sem;
}; };
#endif // AP_NOTIFY_SERIALLED_ENABLED