mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
ported mixer app
This commit is contained in:
parent
ebdf178ba3
commit
8a873df9d0
@ -37,6 +37,8 @@
|
||||
* Mixer utility.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
@ -44,7 +46,6 @@
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <ctype.h>
|
||||
#include <nuttx/compiler.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
@ -58,22 +59,27 @@
|
||||
extern "C" __EXPORT int mixer_main(int argc, char *argv[]);
|
||||
|
||||
static void usage(const char *reason) noreturn_function;
|
||||
static void load(const char *devname, const char *fname) noreturn_function;
|
||||
static int load(const char *devname, const char *fname) noreturn_function;
|
||||
|
||||
int
|
||||
mixer_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2)
|
||||
if (argc < 2) {
|
||||
usage("missing command");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "load")) {
|
||||
if (argc < 4)
|
||||
usage("missing device or filename");
|
||||
|
||||
load(argv[2], argv[3]);
|
||||
int ret = load(argv[2], argv[3]);
|
||||
if(ret !=0) {
|
||||
warnx("failed to load mixer");
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
usage("unrecognised command");
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
@ -84,31 +90,37 @@ usage(const char *reason)
|
||||
|
||||
fprintf(stderr, "usage:\n");
|
||||
fprintf(stderr, " mixer load <device> <filename>\n");
|
||||
/* XXX other useful commands? */
|
||||
exit(1);
|
||||
}
|
||||
|
||||
static void
|
||||
static int
|
||||
load(const char *devname, const char *fname)
|
||||
{
|
||||
int dev;
|
||||
char buf[2048];
|
||||
|
||||
/* open the device */
|
||||
if ((dev = open(devname, 0)) < 0)
|
||||
err(1, "can't open %s\n", devname);
|
||||
if ((dev = px4_open(devname, 0)) < 0) {
|
||||
warnx("can't open %s\n", devname);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* reset mixers on the device */
|
||||
if (ioctl(dev, MIXERIOCRESET, 0))
|
||||
err(1, "can't reset mixers on %s", devname);
|
||||
if (px4_ioctl(dev, MIXERIOCRESET, 0)) {
|
||||
warnx("can't reset mixers on %s", devname);
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (load_mixer_file(fname, &buf[0], sizeof(buf)) < 0)
|
||||
err(1, "can't load mixer: %s", fname);
|
||||
if (load_mixer_file(fname, &buf[0], sizeof(buf)) < 0) {
|
||||
warnx("can't load mixer: %s", fname);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* XXX pass the buffer to the device */
|
||||
int ret = ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf);
|
||||
int ret = px4_ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf);
|
||||
|
||||
if (ret < 0)
|
||||
err(1, "error loading mixers from %s", fname);
|
||||
exit(0);
|
||||
if (ret < 0) {
|
||||
warnx("error loading mixers from %s", fname);
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user