mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Notify: added NTZ_BUZZ_VOLUME parameter
it is fairly non-linear, but does work
This commit is contained in:
parent
5ee66ab6a8
commit
82a98ef95d
@ -158,6 +158,13 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
|
||||
AP_GROUPINFO("BUZZ_ON_LVL", 7, AP_Notify, _buzzer_level, 1),
|
||||
#endif
|
||||
|
||||
// @Param: BUZZ_VOLUME
|
||||
// @DisplayName: Buzzer volume
|
||||
// @Description: Enable or disable the buzzer.
|
||||
// @Range: 0 100
|
||||
// @Units: %
|
||||
AP_GROUPINFO("BUZZ_VOLUME", 8, AP_Notify, _buzzer_volume, 100),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -158,6 +158,7 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
uint8_t get_buzz_pin() const { return _buzzer_pin; }
|
||||
uint8_t get_buzz_level() const { return _buzzer_level; }
|
||||
uint8_t get_buzz_volume() const { return _buzzer_volume; }
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
HAL_Semaphore sf_window_mutex;
|
||||
@ -181,6 +182,7 @@ private:
|
||||
AP_Int8 _buzzer_pin;
|
||||
AP_Int32 _led_type;
|
||||
AP_Int8 _buzzer_level;
|
||||
AP_Int8 _buzzer_volume;
|
||||
|
||||
char _send_text[NOTIFY_TEXT_BUFFER_SIZE];
|
||||
uint32_t _send_text_updated_millis; // last time text changed
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <math.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
@ -297,6 +298,8 @@ void MMLPlayer::next_action()
|
||||
|
||||
float note_frequency = 880.0f * expf(logf(2.0f) * ((int)note - 46) / 12.0f);
|
||||
float note_volume = _volume/255.0f;
|
||||
note_volume *= AP::notify().get_buzz_volume() * 0.01;
|
||||
note_volume = constrain_float(note_volume, 0, 1);
|
||||
|
||||
note_frequency = constrain_float(note_frequency, 10, 22000);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user