PX4 Firmware
PX4 Autopilot Software http://px4.io
tune_control.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file tune_control.cpp
36  *
37  * Command-line tool to control & test the (external) tunes.
38  * To use it make sure there's a driver running, which handles the tune_control uorb topic.
39  */
40 
41 #include <px4_platform_common/getopt.h>
42 #include <px4_platform_common/log.h>
43 
44 #include <stdlib.h>
45 #include <string.h>
46 #include <unistd.h>
47 #include <errno.h>
48 
49 #include <px4_platform_common/module.h>
50 
51 #include <lib/tunes/tunes.h>
53 
54 #include <drivers/drv_hrt.h>
55 
56 #define MAX_NOTE_ITERATION 50
57 
58 static void usage();
59 
60 static orb_advert_t tune_control_pub = nullptr;
61 
62 extern "C" {
63  __EXPORT int tune_control_main(int argc, char *argv[]);
64 }
65 
67 {
68  tune_control.timestamp = hrt_absolute_time();
69 
70  if (tune_control_pub == nullptr) {
71  // We have a minimum of 3 so that tune, stop, tune will fit
72  tune_control_pub = orb_advertise_queue(ORB_ID(tune_control), &tune_control, tune_control_s::ORB_QUEUE_LENGTH);
73 
74  } else {
75  orb_publish(ORB_ID(tune_control), tune_control_pub, &tune_control);
76  }
77 }
78 
79 int
80 tune_control_main(int argc, char *argv[])
81 {
82  Tunes tunes;
83  bool string_input = false;
84  const char *tune_string = nullptr;
85  int myoptind = 1;
86  int ch;
87  const char *myoptarg = nullptr;
88  unsigned int value;
90  tune_control.tune_id = 0;
91  tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT;
92 
93  while ((ch = px4_getopt(argc, argv, "f:d:t:m:s:", &myoptind, &myoptarg)) != EOF) {
94  switch (ch) {
95  case 'f':
96  value = (uint16_t)(strtol(myoptarg, nullptr, 0));
97 
98  if (value > 0 && value < 22000) {
99  tune_control.frequency = value;
100 
101  } else {
102  usage();
103  return 1;
104  }
105 
106  break;
107 
108  case 'd':
109  tune_control.duration = (uint32_t)(strtol(myoptarg, nullptr, 0));
110  break;
111 
112  case 't':
113  value = (uint8_t)(strtol(myoptarg, nullptr, 0));
114 
115  if (value > 0 && value < tunes.get_default_tunes_size()) {
116  tune_control.tune_id = value;
117 
118  } else {
119  usage();
120  return 1;
121  }
122 
123  break;
124 
125  case 'm':
126  string_input = true;
127  tune_string = myoptarg;
128 
129  // check if string is a valid melody string
130  if (tune_string[0] != 'M') {
131  usage();
132  return 1;
133  }
134 
135  break;
136 
137  case 's':
138  value = (uint8_t)(strtol(myoptarg, nullptr, 0));
139 
140  if (value <= tune_control_s::VOLUME_LEVEL_MAX) {
141  tune_control.volume = value;
142 
143  } else {
144  tune_control.volume = tune_control_s::VOLUME_LEVEL_MAX;
145  }
146 
147  break;
148 
149  default:
150  usage();
151  return -1;
152  break;
153  }
154  }
155 
156  if (myoptind >= argc) {
157  usage();
158  return 1;
159  }
160 
161  unsigned frequency, duration, silence;
162  uint8_t volume;
163  int exit_counter = 0;
164 
165  if (!strcmp(argv[myoptind], "play")) {
166  if (string_input) {
167  PX4_INFO("Start playback...");
168  tunes.set_string(tune_string, tune_control.volume);
169 
170  while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
171  tune_control.tune_id = 0;
172  tune_control.frequency = (uint16_t)frequency;
173  tune_control.duration = (uint32_t)duration;
174  tune_control.silence = (uint32_t)silence;
175  tune_control.volume = (uint8_t)volume;
176  publish_tune_control(tune_control);
177  px4_usleep(duration + silence);
178  exit_counter++;
179 
180  // exit if the loop is doing too many iterations
181  if (exit_counter > MAX_NOTE_ITERATION) {
182  break;
183  }
184  }
185 
186  PX4_INFO("Playback finished.");
187 
188  } else { // tune id instead of string has been provided
189  if (tune_control.tune_id == 0) {
190  tune_control.tune_id = 1;
191  }
192 
193  PX4_INFO("Publishing standard tune %d", tune_control.tune_id);
194  publish_tune_control(tune_control);
195  }
196 
197  } else if (!strcmp(argv[myoptind], "libtest")) {
198  int ret = tunes.set_control(tune_control);
199 
200  if (ret == -EINVAL) {
201  PX4_WARN("Tune ID not recognized.");
202  }
203 
204  while (tunes.get_next_note(frequency, duration, silence, volume) > 0) {
205  PX4_INFO("frequency: %d, duration %d, silence %d, volume %d",
206  frequency, duration, silence, volume);
207 
208  px4_usleep(500000);
209  exit_counter++;
210 
211  // exit if the loop is doing too many iterations
212  if (exit_counter > MAX_NOTE_ITERATION) {
213  break;
214  }
215  }
216 
217  } else if (!strcmp(argv[myoptind], "stop")) {
218  PX4_INFO("Stopping playback...");
219  tune_control.tune_id = 0;
220  tune_control.frequency = 0;
221  tune_control.duration = 0;
222  tune_control.silence = 0;
223  tune_control.tune_override = true;
224  publish_tune_control(tune_control);
225 
226  // We wait the maximum update interval to ensure
227  // The stop will not be overwritten
228  px4_usleep(tunes.get_maximum_update_interval());
229 
230  } else {
231  usage();
232  return 1;
233  }
234 
235  return 0;
236 }
237 
238 static void
240 {
241 
242  PRINT_MODULE_DESCRIPTION(
243  R"DESCR_STR(
244 ### Description
245 
246 Command-line tool to control & test the (external) tunes.
247 
248 Tunes are used to provide audible notification and warnings (e.g. when the system arms, gets position lock, etc.).
249 The tool requires that a driver is running that can handle the tune_control uorb topic.
250 
251 Information about the tune format and predefined system tunes can be found here:
252 https://github.com/PX4/Firmware/blob/master/src/lib/tunes/tune_definition.desc
253 
254 ### Examples
255 
256 Play system tune #2:
257 $ tune_control play -t 2
258 )DESCR_STR");
259 
260  PRINT_MODULE_USAGE_NAME("tune_control", "system");
261  PRINT_MODULE_USAGE_COMMAND_DESCR("play","Play system tune or single note.");
262  PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 21, "Play predefined system tune", true);
263  PRINT_MODULE_USAGE_PARAM_INT('f', -1, 0, 22, "Frequency of note in Hz (0-22kHz)", true);
264  PRINT_MODULE_USAGE_PARAM_INT('d', -1, 1, 21, "Duration of note in us", true);
265  PRINT_MODULE_USAGE_PARAM_INT('s', 40, 0, 100, "Volume level (loudness) of the note (0-100)", true);
266  PRINT_MODULE_USAGE_PARAM_STRING('m', nullptr, R"(<string> - e.g. "MFT200e8a8a")",
267  "Melody in string form", true);
268  PRINT_MODULE_USAGE_COMMAND_DESCR("libtest","Test library");
269  PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop playback (use for repeated tunes)");
270 
271 }
int get_next_note(unsigned &frequency, unsigned &duration, unsigned &silence)
Get next note in the current tune, which has been provided by either set_control or play_string...
Definition: tunes.cpp:172
Definition: I2C.hpp:51
High-resolution timer with callouts and timekeeping.
uint64_t timestamp
Definition: tune_control.h:57
orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data, unsigned int queue_size)
Definition: uORB.cpp:48
Library for parsing tunes from melody-strings or dedicated tune messages.
Definition: tunes.h:56
uint8_t tune_override
Definition: tune_control.h:62
__EXPORT int tune_control_main(int argc, char *argv[])
uint16_t frequency
Definition: tune_control.h:60
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
uint32_t duration
Definition: tune_control.h:58
static void publish_tune_control(tune_control_s &tune_control)
static void usage()
static orb_advert_t tune_control_pub
int set_control(const tune_control_s &tune_control)
Set tune to be played using the message.
Definition: tunes.cpp:85
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
#define MAX_NOTE_ITERATION
static tune_control_s tune_control
unsigned int get_default_tunes_size() const
Get the number of default tunes.
Definition: tunes.h:121
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
uint8_t tune_id
Definition: tune_control.h:61
void set_string(const char *const string, uint8_t volume)
Set tune to be played using a string.
Definition: tunes.cpp:138
uint32_t silence
Definition: tune_control.h:59
unsigned int get_maximum_update_interval()
Definition: tunes.h:123
uint8_t volume
Definition: tune_control.h:63