mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
Rename tune_control_s strength to volume to match Nuttx and Linux standard nomenclature for audio (loudness) control.
This commit is contained in:
@@ -7,9 +7,9 @@ uint8 tune_id # tune_id corresponding to TuneID::* from the tune_defaults
|
|||||||
uint8 tune_override # if set to 1 the tune which is playing will be stopped and the new started
|
uint8 tune_override # if set to 1 the tune which is playing will be stopped and the new started
|
||||||
uint16 frequency # in Hz
|
uint16 frequency # in Hz
|
||||||
uint32 duration # in us
|
uint32 duration # in us
|
||||||
uint32 silence # in us
|
uint32 silence # in us
|
||||||
uint8 strength # value between 0-100 if supported by backend
|
uint8 volume # value between 0-100 if supported by backend
|
||||||
|
|
||||||
uint8 STRENGTH_MIN = 0
|
uint8 VOLUME_LEVEL_MIN = 0
|
||||||
uint8 STRENGTH_NORMAL = 40
|
uint8 VOLUME_LEVEL_DEFAULT = 40
|
||||||
uint8 STRENGTH_MAX = 100
|
uint8 VOLUME_LEVEL_MAX = 100
|
||||||
|
|||||||
+12
-12
@@ -100,12 +100,12 @@ int Tunes::set_control(const tune_control_s &tune_control)
|
|||||||
// Reset octave, tempo etc.
|
// Reset octave, tempo etc.
|
||||||
reset(_repeat);
|
reset(_repeat);
|
||||||
|
|
||||||
// Strength will remain valid for the entire tune, unless interrupted.
|
// Volume will remain valid for the entire tune, unless interrupted.
|
||||||
if ((unsigned)tune_control.strength <= TUNE_MAX_STRENGTH) {
|
if (tune_control.volume <= tune_control_s::VOLUME_LEVEL_MAX) {
|
||||||
_strength = (unsigned)tune_control.strength;
|
_volume = tune_control.volume;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
_strength = TUNE_MAX_STRENGTH;
|
_volume = tune_control_s::VOLUME_LEVEL_MAX;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -129,7 +129,7 @@ int Tunes::set_control(const tune_control_s &tune_control)
|
|||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tunes::set_string(const char *const string, uint8_t strength)
|
void Tunes::set_string(const char *const string, uint8_t volume)
|
||||||
{
|
{
|
||||||
// Only play new tune if nothing is being played currently.
|
// Only play new tune if nothing is being played currently.
|
||||||
if (_tune == nullptr) {
|
if (_tune == nullptr) {
|
||||||
@@ -138,26 +138,26 @@ void Tunes::set_string(const char *const string, uint8_t strength)
|
|||||||
_tune_start_ptr = string;
|
_tune_start_ptr = string;
|
||||||
_next_tune = _tune;
|
_next_tune = _tune;
|
||||||
|
|
||||||
if (strength <= TUNE_MAX_STRENGTH) {
|
if (volume <= tune_control_s::VOLUME_LEVEL_MAX) {
|
||||||
_strength = strength;
|
_volume = volume;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
_strength = TUNE_MAX_STRENGTH;
|
_volume = tune_control_s::VOLUME_LEVEL_MAX;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int Tunes::get_next_note(unsigned &frequency, unsigned &duration,
|
int Tunes::get_next_note(unsigned &frequency, unsigned &duration,
|
||||||
unsigned &silence, uint8_t &strength)
|
unsigned &silence, uint8_t &volume)
|
||||||
{
|
{
|
||||||
int ret = get_next_note(frequency, duration, silence);
|
int ret = get_next_note(frequency, duration, silence);
|
||||||
|
|
||||||
// Check if note should not be heard -> adjust strength to 0 to be safe.
|
// Check if note should not be heard -> adjust volume to 0 to be safe.
|
||||||
if (frequency == 0 || duration == 0) {
|
if (frequency == 0 || duration == 0) {
|
||||||
strength = 0;
|
volume = 0;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
strength = _strength;
|
volume = _volume;
|
||||||
}
|
}
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
|
|||||||
@@ -45,7 +45,6 @@
|
|||||||
#define TUNE_DEFAULT_OCTAVE 4
|
#define TUNE_DEFAULT_OCTAVE 4
|
||||||
#define TUNE_DEFAULT_TEMPO 120
|
#define TUNE_DEFAULT_TEMPO 120
|
||||||
|
|
||||||
#define TUNE_MAX_STRENGTH 100
|
|
||||||
#define TUNE_MAX_UPDATE_INTERVAL_US 100000
|
#define TUNE_MAX_UPDATE_INTERVAL_US 100000
|
||||||
|
|
||||||
|
|
||||||
@@ -90,7 +89,7 @@ public:
|
|||||||
*
|
*
|
||||||
* @param string tune input string
|
* @param string tune input string
|
||||||
*/
|
*/
|
||||||
void set_string(const char *const string, uint8_t strength);
|
void set_string(const char *const string, uint8_t volume);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get next note in the current tune, which has been provided by either
|
* Get next note in the current tune, which has been provided by either
|
||||||
@@ -106,13 +105,13 @@ public:
|
|||||||
* Get next note in the current tune, which has been provided by either
|
* Get next note in the current tune, which has been provided by either
|
||||||
* set_control or play_string
|
* set_control or play_string
|
||||||
* @param frequency return frequency value (Hz)
|
* @param frequency return frequency value (Hz)
|
||||||
* @param duration return duration of the tone (us)
|
* @param duration return duration of the note (us)
|
||||||
* @param silence return silence duration (us)
|
* @param silence return silence duration (us)
|
||||||
* @param strength return the strength of the note (between 0-100)
|
* @param volume return the volume level of the note (between 0-100)
|
||||||
* @return -1 for error, 0 for play one tone and 1 for continue a sequence
|
* @return -1 for error, 0 for play one tone and 1 for continue a sequence
|
||||||
*/
|
*/
|
||||||
int get_next_note(unsigned &frequency, unsigned &duration,
|
int get_next_note(unsigned &frequency, unsigned &duration,
|
||||||
unsigned &silence, uint8_t &strength);
|
unsigned &silence, uint8_t &volume);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get the number of default tunes. This is useful for when a tune is
|
* Get the number of default tunes. This is useful for when a tune is
|
||||||
@@ -213,7 +212,7 @@ private:
|
|||||||
unsigned int _duration = 0;
|
unsigned int _duration = 0;
|
||||||
unsigned int _frequency = 0;
|
unsigned int _frequency = 0;
|
||||||
unsigned int _silence = 0;
|
unsigned int _silence = 0;
|
||||||
uint8_t _strength = 0;
|
uint8_t _volume = 0;
|
||||||
|
|
||||||
bool _using_custom_msg = false;
|
bool _using_custom_msg = false;
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -145,7 +145,7 @@ void buzzer_deinit()
|
|||||||
void set_tune_override(int tune)
|
void set_tune_override(int tune)
|
||||||
{
|
{
|
||||||
tune_control.tune_id = tune;
|
tune_control.tune_id = tune;
|
||||||
tune_control.strength = tune_control_s::STRENGTH_NORMAL;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||||
tune_control.tune_override = 1;
|
tune_control.tune_override = 1;
|
||||||
tune_control.timestamp = hrt_absolute_time();
|
tune_control.timestamp = hrt_absolute_time();
|
||||||
orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||||
@@ -160,7 +160,7 @@ void set_tune(int tune)
|
|||||||
/* allow interrupting current non-repeating tune by the same tune */
|
/* allow interrupting current non-repeating tune by the same tune */
|
||||||
if (tune != tune_current || new_tune_duration != 0) {
|
if (tune != tune_current || new_tune_duration != 0) {
|
||||||
tune_control.tune_id = tune;
|
tune_control.tune_id = tune;
|
||||||
tune_control.strength = tune_control_s::STRENGTH_NORMAL;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||||
tune_control.tune_override = 0;
|
tune_control.tune_override = 0;
|
||||||
tune_control.timestamp = hrt_absolute_time();
|
tune_control.timestamp = hrt_absolute_time();
|
||||||
orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||||
|
|||||||
@@ -94,10 +94,10 @@ void RC_Loss_Alarm::process()
|
|||||||
void RC_Loss_Alarm::play_tune()
|
void RC_Loss_Alarm::play_tune()
|
||||||
{
|
{
|
||||||
struct tune_control_s tune_control = {};
|
struct tune_control_s tune_control = {};
|
||||||
tune_control.tune_id = static_cast<int>(TuneID::ERROR_TUNE);
|
tune_control.timestamp = hrt_absolute_time();
|
||||||
tune_control.strength = tune_control_s::STRENGTH_MAX;
|
tune_control.tune_id = static_cast<int>(TuneID::ERROR_TUNE);
|
||||||
tune_control.tune_override = 1;
|
tune_control.tune_override = 1;
|
||||||
tune_control.timestamp = hrt_absolute_time();
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_MAX;
|
||||||
|
|
||||||
if (_tune_control_pub == nullptr) {
|
if (_tune_control_pub == nullptr) {
|
||||||
_tune_control_pub = orb_advertise(ORB_ID(tune_control), &tune_control);
|
_tune_control_pub = orb_advertise(ORB_ID(tune_control), &tune_control);
|
||||||
|
|||||||
@@ -56,7 +56,7 @@ int test_tone(int argc, char *argv[])
|
|||||||
|
|
||||||
if (argc == 1) {
|
if (argc == 1) {
|
||||||
PX4_INFO("Volume silenced for testing predefined tunes 0-20.");
|
PX4_INFO("Volume silenced for testing predefined tunes 0-20.");
|
||||||
tune_control.strength = 0;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_MIN;
|
||||||
|
|
||||||
for (size_t i = 0; i <= 20; i++) {
|
for (size_t i = 0; i <= 20; i++) {
|
||||||
tune_control.tune_id = i;
|
tune_control.tune_id = i;
|
||||||
@@ -80,13 +80,13 @@ int test_tone(int argc, char *argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (argc == 3) {
|
if (argc == 3) {
|
||||||
int volume = 40;
|
int volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||||
Tunes tunes{};
|
Tunes tunes{};
|
||||||
tunes.set_string(argv[2], volume);
|
tunes.set_string(argv[2], volume);
|
||||||
PX4_INFO("Custom tune.");
|
PX4_INFO("Custom tune.");
|
||||||
}
|
}
|
||||||
|
|
||||||
tune_control.strength = 40;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||||
result = orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
result = orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||||
|
|
||||||
orb_unadvertise(tune_control_pub);
|
orb_unadvertise(tune_control_pub);
|
||||||
|
|||||||
@@ -86,11 +86,11 @@ $ tune_control play -t 2
|
|||||||
)DESCR_STR");
|
)DESCR_STR");
|
||||||
|
|
||||||
PRINT_MODULE_USAGE_NAME("tune_control", "system");
|
PRINT_MODULE_USAGE_NAME("tune_control", "system");
|
||||||
PRINT_MODULE_USAGE_COMMAND_DESCR("play","Play system tune, tone, or melody");
|
PRINT_MODULE_USAGE_COMMAND_DESCR("play","Play system tune or single note.");
|
||||||
PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 21, "Play predefined system tune", true);
|
PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 21, "Play predefined system tune", true);
|
||||||
PRINT_MODULE_USAGE_PARAM_INT('f', -1, 0, 22, "Frequency of tone in Hz (0-22kHz)", true);
|
PRINT_MODULE_USAGE_PARAM_INT('f', -1, 0, 22, "Frequency of note in Hz (0-22kHz)", true);
|
||||||
PRINT_MODULE_USAGE_PARAM_INT('d', -1, 1, 21, "Duration of tone in us", true);
|
PRINT_MODULE_USAGE_PARAM_INT('d', -1, 1, 21, "Duration of note in us", true);
|
||||||
PRINT_MODULE_USAGE_PARAM_INT('s', 40, 0, 100, "Strength of tone (0-100)", true);
|
PRINT_MODULE_USAGE_PARAM_INT('s', 40, 0, 100, "Volume level (loudness) of the note (0-100)", true);
|
||||||
PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr, R"(<string> - e.g. "MFT200e8a8a")",
|
PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr, R"(<string> - e.g. "MFT200e8a8a")",
|
||||||
"Melody in string form", true);
|
"Melody in string form", true);
|
||||||
PRINT_MODULE_USAGE_COMMAND_DESCR("libtest","Test library");
|
PRINT_MODULE_USAGE_COMMAND_DESCR("libtest","Test library");
|
||||||
@@ -123,7 +123,7 @@ tune_control_main(int argc, char *argv[])
|
|||||||
unsigned int value;
|
unsigned int value;
|
||||||
tune_control_s tune_control = {};
|
tune_control_s tune_control = {};
|
||||||
tune_control.tune_id = 0;
|
tune_control.tune_id = 0;
|
||||||
tune_control.strength = tune_control_s::STRENGTH_NORMAL;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||||
|
|
||||||
while ((ch = px4_getopt(argc, argv, "f:d:t:m:s:", &myoptind, &myoptarg)) != EOF) {
|
while ((ch = px4_getopt(argc, argv, "f:d:t:m:s:", &myoptind, &myoptarg)) != EOF) {
|
||||||
switch (ch) {
|
switch (ch) {
|
||||||
@@ -172,11 +172,11 @@ tune_control_main(int argc, char *argv[])
|
|||||||
case 's':
|
case 's':
|
||||||
value = (uint8_t)(strtol(myoptarg, nullptr, 0));
|
value = (uint8_t)(strtol(myoptarg, nullptr, 0));
|
||||||
|
|
||||||
if (value > 0 && value < 100) {
|
if (value <= tune_control_s::VOLUME_LEVEL_MAX) {
|
||||||
tune_control.strength = value;
|
tune_control.volume = value;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
tune_control.strength = tune_control_s::STRENGTH_NORMAL;
|
tune_control.volume = tune_control_s::VOLUME_LEVEL_MAX;
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
@@ -194,20 +194,20 @@ tune_control_main(int argc, char *argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
unsigned frequency, duration, silence;
|
unsigned frequency, duration, silence;
|
||||||
uint8_t strength;
|
uint8_t volume;
|
||||||
int exit_counter = 0;
|
int exit_counter = 0;
|
||||||
|
|
||||||
if (!strcmp(argv[myoptind], "play")) {
|
if (!strcmp(argv[myoptind], "play")) {
|
||||||
if (string_input) {
|
if (string_input) {
|
||||||
PX4_INFO("Start playback...");
|
PX4_INFO("Start playback...");
|
||||||
tunes.set_string(tune_string, tune_control.strength);
|
tunes.set_string(tune_string, tune_control.volume);
|
||||||
|
|
||||||
while (tunes.get_next_note(frequency, duration, silence, strength) > 0) {
|
while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
|
||||||
tune_control.tune_id = 0;
|
tune_control.tune_id = 0;
|
||||||
tune_control.frequency = (uint16_t)frequency;
|
tune_control.frequency = (uint16_t)frequency;
|
||||||
tune_control.duration = (uint32_t)duration;
|
tune_control.duration = (uint32_t)duration;
|
||||||
tune_control.silence = (uint32_t)silence;
|
tune_control.silence = (uint32_t)silence;
|
||||||
tune_control.strength = (uint8_t)strength;
|
tune_control.volume = (uint8_t)volume;
|
||||||
publish_tune_control(tune_control);
|
publish_tune_control(tune_control);
|
||||||
px4_usleep(duration + silence);
|
px4_usleep(duration + silence);
|
||||||
exit_counter++;
|
exit_counter++;
|
||||||
@@ -236,9 +236,10 @@ tune_control_main(int argc, char *argv[])
|
|||||||
PX4_WARN("Tune ID not recognized.");
|
PX4_WARN("Tune ID not recognized.");
|
||||||
}
|
}
|
||||||
|
|
||||||
while (tunes.get_next_note(frequency, duration, silence, strength) > 0) {
|
while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
|
||||||
PX4_INFO("frequency: %d, duration %d, silence %d, strength%d",
|
PX4_INFO("frequency: %d, duration %d, silence %d, volume %d",
|
||||||
frequency, duration, silence, strength);
|
frequency, duration, silence, volume);
|
||||||
|
|
||||||
px4_usleep(500000);
|
px4_usleep(500000);
|
||||||
exit_counter++;
|
exit_counter++;
|
||||||
|
|
||||||
@@ -256,6 +257,7 @@ tune_control_main(int argc, char *argv[])
|
|||||||
tune_control.silence = 0;
|
tune_control.silence = 0;
|
||||||
tune_control.tune_override = true;
|
tune_control.tune_override = true;
|
||||||
publish_tune_control(tune_control);
|
publish_tune_control(tune_control);
|
||||||
|
|
||||||
// We wait the maximum update interval to ensure
|
// We wait the maximum update interval to ensure
|
||||||
// The stop will not be overwritten
|
// The stop will not be overwritten
|
||||||
px4_usleep(tunes.get_maximum_update_interval());
|
px4_usleep(tunes.get_maximum_update_interval());
|
||||||
|
|||||||
Reference in New Issue
Block a user