mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Notify: allow external leds to be disabled
This commit is contained in:
parent
e978a710cc
commit
aae18f9ead
@ -20,8 +20,10 @@
|
|||||||
struct AP_Notify::notify_type AP_Notify::flags;
|
struct AP_Notify::notify_type AP_Notify::flags;
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
void AP_Notify::init(void)
|
void AP_Notify::init(bool enable_external_leds)
|
||||||
{
|
{
|
||||||
|
AP_Notify::flags.external_leds = enable_external_leds;
|
||||||
|
|
||||||
boardled.init();
|
boardled.init();
|
||||||
toshibaled.init();
|
toshibaled.init();
|
||||||
|
|
||||||
|
@ -41,7 +41,10 @@ public:
|
|||||||
uint16_t esc_calibration : 1; // 1 if calibrating escs
|
uint16_t esc_calibration : 1; // 1 if calibrating escs
|
||||||
uint16_t failsafe_radio : 1; // 1 if radio failsafe
|
uint16_t failsafe_radio : 1; // 1 if radio failsafe
|
||||||
uint16_t failsafe_battery : 1; // 1 if battery failsafe
|
uint16_t failsafe_battery : 1; // 1 if battery failsafe
|
||||||
uint16_t failsafe_gps : 1; // 1 if gps failsafe
|
uint16_t failsafe_gps : 1; // 1 if gps failsafe
|
||||||
|
|
||||||
|
// additional flags
|
||||||
|
uint16_t external_leds : 1; // 1 if external LEDs are enabled (normally only used for copter)
|
||||||
};
|
};
|
||||||
|
|
||||||
// the notify flags are static to allow direct class access
|
// the notify flags are static to allow direct class access
|
||||||
@ -49,7 +52,7 @@ public:
|
|||||||
static struct notify_type flags;
|
static struct notify_type flags;
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
void init(void);
|
void init(bool enable_external_leds);
|
||||||
|
|
||||||
/// update - allow updates of leds that cannot be updated during a timed interrupt
|
/// update - allow updates of leds that cannot be updated during a timed interrupt
|
||||||
void update(void);
|
void update(void);
|
||||||
|
@ -22,6 +22,11 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
void ExternalLED::init(void)
|
void ExternalLED::init(void)
|
||||||
{
|
{
|
||||||
|
// return immediately if disabled
|
||||||
|
if (!AP_Notify::flags.external_leds) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// setup the main LEDs as outputs
|
// setup the main LEDs as outputs
|
||||||
hal.gpio->pinMode(EXTERNAL_LED_ARMED, GPIO_OUTPUT);
|
hal.gpio->pinMode(EXTERNAL_LED_ARMED, GPIO_OUTPUT);
|
||||||
hal.gpio->pinMode(EXTERNAL_LED_GPS, GPIO_OUTPUT);
|
hal.gpio->pinMode(EXTERNAL_LED_GPS, GPIO_OUTPUT);
|
||||||
@ -40,6 +45,11 @@ void ExternalLED::init(void)
|
|||||||
*/
|
*/
|
||||||
void ExternalLED::update(void)
|
void ExternalLED::update(void)
|
||||||
{
|
{
|
||||||
|
// return immediately if disabled
|
||||||
|
if (!AP_Notify::flags.external_leds) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// reduce update rate from 50hz to 10hz
|
// reduce update rate from 50hz to 10hz
|
||||||
_counter++;
|
_counter++;
|
||||||
if (_counter < 5) {
|
if (_counter < 5) {
|
||||||
|
Loading…
Reference in New Issue
Block a user