Skip to content

Commit

Permalink
working
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Apr 15, 2024
1 parent 95eb828 commit 7de5ab1
Show file tree
Hide file tree
Showing 11 changed files with 51 additions and 51 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -956,11 +956,11 @@ const AP_Param::Info Plane::var_info[] = {



#if HAL_NAVEKF3_AVAILABLE

// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
#endif



// @Group: RPM
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -390,9 +390,9 @@
#define HAL_BUTTON_ENABLED 0
#endif

#ifndef AP_NOTIFY_SCRIPTING_LED_ENABLED
#define AP_NOTIFY_SCRIPTING_LED_ENABLED 0
#endif




#ifndef AP_PARAM_DYNAMIC_ENABLED
#define AP_PARAM_DYNAMIC_ENABLED 0
Expand Down
24 changes: 12 additions & 12 deletions libraries/AP_Notify/AP_Notify.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,14 +195,14 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
AP_GROUPINFO("DISPLAY_TYPE", 3, AP_Notify, _display_type, 0),
#endif

#if AP_NOTIFY_OREOLED_ENABLED

// @Param: OREO_THEME
// @DisplayName: OreoLED Theme
// @Description: Enable/Disable Solo Oreo LED driver, 0 to disable, 1 for Aircraft theme, 2 for Rover theme
// @Values: 0:Disabled,1:Aircraft,2:Rover
// @User: Advanced
AP_GROUPINFO("OREO_THEME", 4, AP_Notify, _oreo_theme, 0),
#endif


// @Param: BUZZ_PIN
// @DisplayName: Buzzer pin
Expand Down Expand Up @@ -355,33 +355,33 @@ void AP_Notify::add_backends(void)
ADD_BACKEND(new ProfiLED());
break;

#if AP_NOTIFY_PROFILED_SPI_ENABLED

case Notify_LED_ProfiLED_SPI:
ADD_BACKEND(new ProfiLED_SPI());
break;
#endif
#if AP_NOTIFY_OREOLED_ENABLED


case Notify_LED_OreoLED:
if (_oreo_theme) {
ADD_BACKEND(new OreoLED_I2C(0, _oreo_theme));
}
break;
#endif

#if AP_NOTIFY_DRONECAN_LED_ENABLED
case Notify_LED_DroneCAN:
ADD_BACKEND(new DroneCAN_RGB_LED());
break;
#endif // AP_NOTIFY_DRONECAN_LED_ENABLED
#if AP_NOTIFY_SCRIPTING_LED_ENABLED

case Notify_LED_Scripting:
ADD_BACKEND(new ScriptingLED());
break;
#endif
#if AP_NOTIFY_DSHOT_LED_ENABLED


case Notify_LED_DShot:
ADD_BACKEND(new DShotLED());
break;
#endif


case Notify_LED_LP5562_I2C_External:
FOREACH_I2C_EXTERNAL(b) {
Expand All @@ -406,14 +406,14 @@ void AP_Notify::add_backends(void)
}
break;

#if AP_NOTIFY_DISCRETE_RGB_ENABLED

case Notify_LED_DiscreteRGB:
ADD_BACKEND(new DiscreteRGBLed(DISCRETE_RGB_RED_PIN,
DISCRETE_RGB_GREEN_PIN,
DISCRETE_RGB_BLUE_PIN,
DISCRETE_RGB_POLARITY));
break;
#endif

}
}

Expand Down
20 changes: 10 additions & 10 deletions libraries/AP_Notify/AP_Notify.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,9 @@ class AP_Notify

Notify_LED_PCA9685LED_I2C_External = (1 << 3), // External PCA9685_I2C

#if AP_NOTIFY_OREOLED_ENABLED

Notify_LED_OreoLED = (1 << 4), // Oreo
#endif

#if AP_NOTIFY_DRONECAN_LED_ENABLED
Notify_LED_DroneCAN = (1 << 5), // UAVCAN RGB LED
#endif
Expand All @@ -77,15 +77,15 @@ class AP_Notify

Notify_LED_ProfiLED = (1 << 9), // ProfiLED

#if AP_NOTIFY_SCRIPTING_LED_ENABLED

Notify_LED_Scripting = (1 << 10),// Colour accessor for scripting
#endif
#if AP_NOTIFY_DSHOT_LED_ENABLED


Notify_LED_DShot = (1 << 11),// Use dshot commands to set ESC LEDs
#endif
#if AP_NOTIFY_PROFILED_SPI_ENABLED


Notify_LED_ProfiLED_SPI = (1 << 12), // ProfiLED (SPI)
#endif


Notify_LED_LP5562_I2C_External = (1 << 13), // LP5562
Notify_LED_LP5562_I2C_Internal = (1 << 14), // LP5562
Expand All @@ -94,9 +94,9 @@ class AP_Notify
Notify_LED_IS31FL3195_I2C_External = (1 << 15), // IS31FL3195
Notify_LED_IS31FL3195_I2C_Internal = (1 << 16), // IS31FL3195

#if AP_NOTIFY_DISCRETE_RGB_ENABLED

Notify_LED_DiscreteRGB = (1 << 17), // DiscreteRGB
#endif


Notify_LED_NeoPixelRGB = (1 << 18), // NeoPixel AdaFruit 4544 Worldsemi WS2811

Expand Down
24 changes: 12 additions & 12 deletions libraries/AP_Notify/AP_Notify_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@
#include <AP_SerialLED/AP_SerialLED_config.h>
#include <AP_Scripting/AP_Scripting_config.h>

#ifndef AP_NOTIFY_DISCRETE_RGB_ENABLED
#define AP_NOTIFY_DISCRETE_RGB_ENABLED 0
#endif




#ifndef HAL_DISPLAY_ENABLED
#define HAL_DISPLAY_ENABLED 1
Expand All @@ -21,9 +21,9 @@
#define AP_NOTIFY_DRONECAN_LED_ENABLED HAL_ENABLE_DRONECAN_DRIVERS
#endif

#ifndef AP_NOTIFY_DSHOT_LED_ENABLED
#define AP_NOTIFY_DSHOT_LED_ENABLED HAL_SUPPORT_RCOUT_SERIAL
#endif




#ifndef AP_NOTIFY_VRBOARD_LED_ENABLED
#define AP_NOTIFY_VRBOARD_LED_ENABLED 0
Expand Down Expand Up @@ -57,9 +57,9 @@



#ifndef AP_NOTIFY_PROFILED_SPI_ENABLED
#define AP_NOTIFY_PROFILED_SPI_ENABLED 0 // requires hwdef to have SPI line
#endif




#ifndef AP_NOTIFY_SCRIPTING_LED_ENABLED
#define AP_NOTIFY_SCRIPTING_LED_ENABLED AP_SCRIPTING_ENABLED
Expand All @@ -73,9 +73,9 @@



#ifndef AP_NOTIFY_OREOLED_ENABLED
#define AP_NOTIFY_OREOLED_ENABLED 0
#endif




// Serial LED backends:

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Notify/DiscreteRGBLed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

#include "AP_Notify_config.h"

#if AP_NOTIFY_DISCRETE_RGB_ENABLED


#include "DiscreteRGBLed.h"

Expand Down Expand Up @@ -60,4 +60,4 @@ bool DiscreteRGBLed::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue)
return true;
}

#endif // AP_NOTIFY_DISCRETE_RGB_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Notify/DiscreteRGBLed.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

#include "AP_Notify_config.h"

#if AP_NOTIFY_DISCRETE_RGB_ENABLED


#include "RGBLed.h"

Expand All @@ -40,4 +40,4 @@ class DiscreteRGBLed: public RGBLed {
uint16_t red_pin_number, green_pin_number, blue_pin_number;
};

#endif // AP_NOTIFY_DISCRETE_RGB_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Notify/OreoLED_I2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "OreoLED_I2C.h"

#if AP_NOTIFY_OREOLED_ENABLED


#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
Expand Down Expand Up @@ -713,4 +713,4 @@ bool OreoLED_I2C::oreo_state::operator==(const OreoLED_I2C::oreo_state &os) cons
&& (os.period==period) && (os.repeat==repeat) && (os.phase_offset==phase_offset));
}

#endif // AP_NOTIFY_OREOLED_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Notify/OreoLED_I2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "AP_Notify_config.h"

#if AP_NOTIFY_OREOLED_ENABLED


#include <AP_HAL/AP_HAL.h>
#include "NotifyDevice.h"
Expand Down Expand Up @@ -203,4 +203,4 @@ class OreoLED_I2C : public NotifyDevice {
uint32_t _last_sync_ms;
};

#endif // AP_NOTIFY_OREOLED_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Notify/ProfiLED.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ uint16_t ProfiLED::init_ports()
}


#if AP_NOTIFY_PROFILED_SPI_ENABLED

ProfiLED_SPI::ProfiLED_SPI() :
RGBLed(ProfiLED_OFF, ProfiLED_HIGH, ProfiLED_MEDIUM, ProfiLED_LOW) {}

Expand Down Expand Up @@ -168,4 +168,4 @@ void ProfiLED_SPI::update_led_strip() {
}
}

#endif // AP_NOTIFY_PROFILED_SPI_ENABLED

4 changes: 2 additions & 2 deletions libraries/AP_Notify/ProfiLED.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class ProfiLED: public SerialLED {
};


#if AP_NOTIFY_PROFILED_SPI_ENABLED

#include <AP_HAL/SPIDevice.h>
#include "RGBLed.h"

Expand Down Expand Up @@ -63,4 +63,4 @@ class ProfiLED_SPI: public RGBLed {
};


#endif // AP_NOTIFY_PROFILED_SPI_ENABLED

0 comments on commit 7de5ab1

Please sign in to comment.