AP_Notify: add support for dshot command beeps

add support for ESC LEDs triggered by dshot commands
don't send DShot LED commands when armed
make enablement of dshot buzzer and LEDs configurable
This commit is contained in:
Andy Piper 2021-04-03 23:01:55 +01:00 committed by Andrew Tridgell
parent ba96f4491d
commit e710799b12
5 changed files with 91 additions and 10 deletions

View File

@ -38,6 +38,7 @@
#include "AP_BoardLED2.h"
#include "ProfiLED.h"
#include "ScriptingLED.h"
#include "DShotLED.h"
extern const AP_HAL::HAL& hal;
@ -96,6 +97,14 @@ AP_Notify *AP_Notify::_singleton;
#define BUZZER_ENABLE_DEFAULT 1
#endif
#ifndef BUILD_DEFAULT_BUZZER_TYPE
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && HAL_DSHOT_ALARM
#define BUILD_DEFAULT_BUZZER_TYPE (BUZZER_ENABLE_DEFAULT | (HAL_DSHOT_ALARM << 1))
#else
#define BUILD_DEFAULT_BUZZER_TYPE BUZZER_ENABLE_DEFAULT
#endif
#endif
#ifndef NOTIFY_LED_BRIGHT_DEFAULT
#define NOTIFY_LED_BRIGHT_DEFAULT RGB_LED_HIGH
#endif
@ -122,12 +131,12 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
// @User: Advanced
AP_GROUPINFO("LED_BRIGHT", 0, AP_Notify, _rgb_led_brightness, NOTIFY_LED_BRIGHT_DEFAULT),
// @Param: BUZZ_ENABLE
// @DisplayName: Buzzer enable
// @Description: Enable or disable the buzzer.
// @Values: 0:Disable,1:Enable
// @Param: BUZZ_TYPES
// @DisplayName: Buzzer Driver Types
// @Description: Controls what types of Buzzer will be enabled
// @Bitmask: 0:Built-in buzzer, 1:DShot
// @User: Advanced
AP_GROUPINFO("BUZZ_ENABLE", 1, AP_Notify, _buzzer_enable, BUZZER_ENABLE_DEFAULT),
AP_GROUPINFO("BUZZ_TYPES", 1, AP_Notify, _buzzer_type, BUILD_DEFAULT_BUZZER_TYPE),
// @Param: LED_OVERRIDE
// @DisplayName: Specifies colour source for the RGBLed
@ -164,7 +173,7 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
// @Param: LED_TYPES
// @DisplayName: LED Driver Types
// @Description: Controls what types of LEDs will be enabled
// @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:UAVCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting
// @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:UAVCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting, 11:DShot
// @User: Advanced
AP_GROUPINFO("LED_TYPES", 6, AP_Notify, _led_type, BUILD_DEFAULT_LED_TYPE),
@ -313,6 +322,11 @@ void AP_Notify::add_backends(void)
#endif
break;
case Notify_LED_DShot:
#if HAL_SUPPORT_RCOUT_SERIAL
ADD_BACKEND(new DShotLED());
#endif
break;
}
}
@ -323,7 +337,7 @@ void AP_Notify::add_backends(void)
// ChibiOS noise makers
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
ADD_BACKEND(new Buzzer());
#ifdef HAL_PWM_ALARM
#if defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM
ADD_BACKEND(new AP_ToneAlarm());
#endif

View File

@ -72,6 +72,7 @@ public:
Notify_LED_NeoPixel = (1 << 8), // NeoPixel 5050 AdaFruit 1655 SK6812 Worldsemi WS2812B
Notify_LED_ProfiLED = (1 << 9), // ProfiLED
Notify_LED_Scripting = (1 << 10),// Colour accessor for scripting
Notify_LED_DShot = (1 << 11),// Use dshot commands to set ESC LEDs
Notify_LED_MAX
};
@ -155,7 +156,9 @@ public:
// play a tune string
static void play_tune(const char *tune);
bool buzzer_enabled() const { return _buzzer_enable; }
bool buzzer_enabled() const { return _buzzer_type != 0; }
uint8_t get_buzzer_types() const { return _buzzer_type; }
// set flight mode string
void set_flight_mode_str(const char *str);
@ -189,7 +192,7 @@ private:
// parameters
AP_Int8 _rgb_led_brightness;
AP_Int8 _rgb_led_override;
AP_Int8 _buzzer_enable;
AP_Int8 _buzzer_type;
AP_Int8 _display_type;
AP_Int8 _oreo_theme;
AP_Int8 _buzzer_pin;

View File

@ -0,0 +1,35 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_Notify/AP_Notify.h"
#include <AP_HAL/RCOutput.h>
#include "DShotLED.h"
#include "SRV_Channel/SRV_Channel.h"
extern const AP_HAL::HAL& hal;
bool DShotLED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue)
{
// don't play the motor LEDs while flying
if (hal.util->get_soft_armed() || hal.rcout->get_dshot_esc_type() != AP_HAL::RCOutput::DSHOT_ESC_BLHELI) {
return false;
}
hal.rcout->send_dshot_command(red ? AP_HAL::RCOutput::DSHOT_LED1_ON : AP_HAL::RCOutput::DSHOT_LED1_OFF);
hal.rcout->send_dshot_command(green ? AP_HAL::RCOutput::DSHOT_LED2_ON : AP_HAL::RCOutput::DSHOT_LED2_OFF);
hal.rcout->send_dshot_command(blue ? AP_HAL::RCOutput::DSHOT_LED0_ON : AP_HAL::RCOutput::DSHOT_LED0_OFF);
return true;
}

View File

@ -0,0 +1,29 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "RGBLed.h"
#include "DShotLED.h"
#include <AP_Common/AP_Common.h>
class DShotLED : public RGBLed {
public:
DShotLED() : RGBLed(0, 1, 1, 1) {}
bool init(void) override { return true; }
protected:
bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override;
};

View File

@ -105,7 +105,7 @@ bool AP_ToneAlarm::init()
if (pNotify->buzzer_enabled() == false) {
return false;
}
if (!hal.util->toneAlarm_init()) {
if (!hal.util->toneAlarm_init(pNotify->get_buzzer_types())) {
return false;
}