mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 18:27:35 +08:00
drivers/tone_alarm and tune_control small improvements/cleanup
- drivers/tone_alarm: move to ModuleBase and purge CDev (/dev/tone_alarm0) - drivers/tone_alarm: only run on tune_control publication (or scheduled note) rather than continuously - drivers/tone_alarm: use HRT to schedule tone stop (prevents potential disruption) - msg/tune_control: add tune_id numbering - systemcmds/tune_control: add "error" special case tune_id - move all tune_control publication to new uORB::PublicationQueued<> - start tone_alarm immediately after board defaults are loaded to fix potential startup issues - for SITL (or other boards with no TONE output) print common messages (startup, error, etc)
This commit is contained in:
@@ -69,7 +69,6 @@ set(srcs
|
||||
test_servo.c
|
||||
test_sleep.c
|
||||
test_smooth_z.cpp
|
||||
test_tone.cpp
|
||||
test_uart_baudchange.c
|
||||
test_uart_console.c
|
||||
test_uart_loopback.c
|
||||
|
||||
@@ -1,95 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2019 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file test_tone.cpp
|
||||
* Test for audio tones.
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_tone_alarm.h>
|
||||
#include <lib/tunes/tunes.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <uORB/topics/tune_control.h>
|
||||
|
||||
#include "tests_main.h"
|
||||
|
||||
int test_tone(int argc, char *argv[])
|
||||
{
|
||||
int result = PX4_ERROR;
|
||||
tune_control_s tune_control = {};
|
||||
tune_control.tune_id = static_cast<int>(TuneID::NOTIFY_NEGATIVE);
|
||||
|
||||
orb_advert_t tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control,
|
||||
tune_control_s::ORB_QUEUE_LENGTH);
|
||||
|
||||
if (argc == 1) {
|
||||
PX4_INFO("Volume silenced for testing predefined tunes 0-20.");
|
||||
tune_control.volume = tune_control_s::VOLUME_LEVEL_MIN;
|
||||
|
||||
for (size_t i = 0; i <= 20; i++) {
|
||||
tune_control.tune_id = i;
|
||||
result = orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||
|
||||
if (result != PX4_OK) {
|
||||
PX4_INFO("Error publishing TuneID: %d", tune_control.tune_id);
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
tune_control.tune_id = static_cast<int>(TuneID::NOTIFY_POSITIVE);
|
||||
}
|
||||
|
||||
if (argc == 2) {
|
||||
tune_control.tune_id = atoi(argv[1]);
|
||||
|
||||
if (tune_control.tune_id <= 20) {
|
||||
PX4_INFO("TuneID: %d", tune_control.tune_id);
|
||||
}
|
||||
}
|
||||
|
||||
if (argc == 3) {
|
||||
int volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||
Tunes tunes{};
|
||||
tunes.set_string(argv[2], volume);
|
||||
PX4_INFO("Custom tune.");
|
||||
}
|
||||
|
||||
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||
result = orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||
|
||||
orb_unadvertise(tune_control_pub);
|
||||
return result;
|
||||
}
|
||||
@@ -41,6 +41,7 @@
|
||||
#include "tests_main.h"
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
@@ -114,7 +115,6 @@ const struct {
|
||||
{"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"sleep", test_sleep, OPT_NOJIGTEST},
|
||||
{"smoothz", test_smooth_z, 0},
|
||||
{"tone", test_tone, 0},
|
||||
{"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"versioning", test_versioning, 0},
|
||||
@@ -246,51 +246,26 @@ test_runner(unsigned option)
|
||||
return (failcount > 0);
|
||||
}
|
||||
|
||||
__EXPORT int tests_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Executes system tests.
|
||||
*/
|
||||
int tests_main(int argc, char *argv[])
|
||||
__EXPORT int tests_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
printf("tests: missing test name - 'tests help' for a list of tests\n");
|
||||
PX4_WARN("tests: missing test name - 'tests help' for a list of tests");
|
||||
return 1;
|
||||
}
|
||||
|
||||
int tone_test_index = -1;
|
||||
char *tone_test = {"tone"};
|
||||
char *tone_fail[2] = {NULL, "2"};
|
||||
char *tone_pass[2] = {NULL, "14"};
|
||||
|
||||
// Identify the tone test index for later use.
|
||||
for (size_t i = 0; tests[i].name; i++) {
|
||||
if (*tone_test == *tests[i].name) {
|
||||
tone_test_index = i;
|
||||
}
|
||||
}
|
||||
|
||||
for (size_t i = 0; tests[i].name; i++) {
|
||||
if (!strcmp(tests[i].name, argv[1])) {
|
||||
if (tests[i].fn(argc - 1, argv + 1) == 0) {
|
||||
if (tone_test_index != -1) {
|
||||
tests[tone_test_index].fn(2, tone_pass); // Play a notification.
|
||||
}
|
||||
|
||||
printf("%s PASSED\n", tests[i].name);
|
||||
PX4_INFO("%s PASSED", tests[i].name);
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
if (tone_test_index != -1) {
|
||||
tests[tone_test_index].fn(2, tone_fail); // Play an error notification.
|
||||
}
|
||||
|
||||
printf("%s FAILED\n", tests[i].name);
|
||||
PX4_ERR("%s FAILED", tests[i].name);
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
printf("tests: no test called '%s' - 'tests help' for a list of tests\n", argv[1]);
|
||||
PX4_WARN("tests: no test called '%s' - 'tests help' for a list of tests", argv[1]);
|
||||
return 1;
|
||||
}
|
||||
|
||||
@@ -82,7 +82,6 @@ extern int test_servo(int argc, char *argv[]);
|
||||
extern int test_sleep(int argc, char *argv[]);
|
||||
extern int test_smooth_z(int argc, char *argv[]);
|
||||
extern int test_time(int argc, char *argv[]);
|
||||
extern int test_tone(int argc, char *argv[]);
|
||||
extern int test_uart_baudchange(int argc, char *argv[]);
|
||||
extern int test_uart_break(int argc, char *argv[]);
|
||||
extern int test_uart_console(int argc, char *argv[]);
|
||||
|
||||
@@ -33,6 +33,8 @@
|
||||
px4_add_module(
|
||||
MODULE systemcmds__tune_control
|
||||
MAIN tune_control
|
||||
PRIORITY
|
||||
"SCHED_PRIORITY_MAX - 16" # max priority below high priority WQ threads
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
tune_control.cpp
|
||||
|
||||
@@ -49,35 +49,23 @@
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
#include <lib/tunes/tunes.h>
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/tune_control.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#define MAX_NOTE_ITERATION 50
|
||||
|
||||
static void usage();
|
||||
|
||||
static orb_advert_t tune_control_pub = nullptr;
|
||||
|
||||
extern "C" {
|
||||
__EXPORT int tune_control_main(int argc, char *argv[]);
|
||||
}
|
||||
static void usage();
|
||||
|
||||
static void publish_tune_control(tune_control_s &tune_control)
|
||||
{
|
||||
uORB::PublicationQueued<tune_control_s> tune_control_pub{ORB_ID(tune_control)};
|
||||
tune_control.timestamp = hrt_absolute_time();
|
||||
|
||||
if (tune_control_pub == nullptr) {
|
||||
// We have a minimum of 3 so that tune, stop, tune will fit
|
||||
tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control, tune_control_s::ORB_QUEUE_LENGTH);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
|
||||
}
|
||||
tune_control_pub.publish(tune_control);
|
||||
}
|
||||
|
||||
int
|
||||
tune_control_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int tune_control_main(int argc, char *argv[])
|
||||
{
|
||||
Tunes tunes;
|
||||
bool string_input = false;
|
||||
@@ -86,8 +74,7 @@ tune_control_main(int argc, char *argv[])
|
||||
int ch;
|
||||
const char *myoptarg = nullptr;
|
||||
unsigned int value;
|
||||
tune_control_s tune_control = {};
|
||||
tune_control.tune_id = 0;
|
||||
tune_control_s tune_control{};
|
||||
tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "f:d:t:m:s:", &myoptind, &myoptarg)) != EOF) {
|
||||
@@ -163,11 +150,15 @@ tune_control_main(int argc, char *argv[])
|
||||
int exit_counter = 0;
|
||||
|
||||
if (!strcmp(argv[myoptind], "play")) {
|
||||
if (string_input) {
|
||||
if (argc >= 2 && !strcmp(argv[2], "error")) {
|
||||
tune_control.tune_id = tune_control_s::TUNE_ID_ERROR;
|
||||
publish_tune_control(tune_control);
|
||||
|
||||
} else if (string_input) {
|
||||
PX4_INFO("Start playback...");
|
||||
tunes.set_string(tune_string, tune_control.volume);
|
||||
|
||||
while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
|
||||
while (tunes.get_next_note(frequency, duration, silence, volume) == Tunes::Status::Continue) {
|
||||
tune_control.tune_id = 0;
|
||||
tune_control.frequency = (uint16_t)frequency;
|
||||
tune_control.duration = (uint32_t)duration;
|
||||
@@ -185,12 +176,13 @@ tune_control_main(int argc, char *argv[])
|
||||
|
||||
PX4_INFO("Playback finished.");
|
||||
|
||||
} else { // tune id instead of string has been provided
|
||||
} else {
|
||||
// tune id instead of string has been provided
|
||||
if (tune_control.tune_id == 0) {
|
||||
tune_control.tune_id = 1;
|
||||
}
|
||||
|
||||
PX4_INFO("Publishing standard tune %d", tune_control.tune_id);
|
||||
PX4_DEBUG("Publishing standard tune %d", tune_control.tune_id);
|
||||
publish_tune_control(tune_control);
|
||||
}
|
||||
|
||||
@@ -201,7 +193,7 @@ tune_control_main(int argc, char *argv[])
|
||||
PX4_WARN("Tune ID not recognized.");
|
||||
}
|
||||
|
||||
while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
|
||||
while (tunes.get_next_note(frequency, duration, silence, volume) == Tunes::Status::Continue) {
|
||||
PX4_INFO("frequency: %d, duration %d, silence %d, volume %d",
|
||||
frequency, duration, silence, volume);
|
||||
|
||||
@@ -235,10 +227,8 @@ tune_control_main(int argc, char *argv[])
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
usage()
|
||||
static void usage()
|
||||
{
|
||||
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
@@ -258,14 +248,12 @@ $ tune_control play -t 2
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("tune_control", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("play","Play system tune or single note.");
|
||||
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('f', -1, 0, 22, "Frequency of note in Hz (0-22kHz)", 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, "Volume level (loudness) of the note (0-100)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr, R"(<string> - e.g. "MFT200e8a8a")",
|
||||
"Melody in string form", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("libtest","Test library");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop playback (use for repeated tunes)");
|
||||
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr, R"(<string> - e.g. "MFT200e8a8a")", "Melody in string form", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("libtest", "Test library");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop playback (use for repeated tunes)");
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user