HAL_PX4: added -d command line option to app

allows control of serial device
This commit is contained in:
Andrew Tridgell 2013-01-14 15:59:54 +11:00
parent 64a8a8e4c9
commit bd9c61562f
2 changed files with 65 additions and 33 deletions

View File

@ -39,12 +39,12 @@ static PX4EEPROMStorage storageDriver;
static PX4RCInput rcinDriver; static PX4RCInput rcinDriver;
static PX4RCOutput rcoutDriver; static PX4RCOutput rcoutDriver;
#define UARTA_DEVICE "/dev/ttyS2" #define UARTA_DEFAULT_DEVICE "/dev/ttyS0"
#define UARTB_DEVICE "/dev/ttyS3" #define UARTB_DEFAULT_DEVICE "/dev/ttyS3"
// only two real UART drivers for now // only two real UART drivers for now
static PX4UARTDriver uartADriver(UARTA_DEVICE); static PX4UARTDriver uartADriver(UARTA_DEFAULT_DEVICE);
static PX4UARTDriver uartBDriver(UARTB_DEVICE); static PX4UARTDriver uartBDriver(UARTB_DEFAULT_DEVICE);
static Empty::EmptyUARTDriver uartCDriver; static Empty::EmptyUARTDriver uartCDriver;
HAL_PX4::HAL_PX4() : HAL_PX4::HAL_PX4() :
@ -84,59 +84,87 @@ static int main_loop(int argc, char **argv)
setup(); setup();
hal.scheduler->system_initialized(); hal.scheduler->system_initialized();
while (true) { while (!thread_should_exit) {
loop(); loop();
// yield the CPU for 1ms between loops to let other apps // yield the CPU for 1ms between loops to let other apps
// get some CPU time // get some CPU time
poll(NULL, 0, 1); poll(NULL, 0, 1);
} }
thread_running = false;
return 0; return 0;
} }
static void usage(void)
{
printf("Usage: %s [options] {start,stop,status}\n", SKETCHNAME);
printf("Options:\n");
printf("\t-d DEVICE set terminal device (default %s)\n", UARTA_DEFAULT_DEVICE);
printf("\n");
}
void HAL_PX4::init(int argc, char * const argv[]) const void HAL_PX4::init(int argc, char * const argv[]) const
{ {
int i;
const char *device = UARTA_DEFAULT_DEVICE;
if (argc < 1) { if (argc < 1) {
printf("%s: missing command (try '%s start')", printf("%s: missing command (try '%s start')",
SKETCHNAME, SKETCHNAME); SKETCHNAME, SKETCHNAME);
usage();
exit(1); exit(1);
} }
if (strcmp(argv[1], "start") == 0) { for (i=0; i<argc; i++) {
if (thread_running) { if (strcmp(argv[i], "start") == 0) {
printf("%s already running\n", SKETCHNAME); if (thread_running) {
/* this is not an error */ printf("%s already running\n", SKETCHNAME);
exit(0); /* this is not an error */
} exit(0);
}
printf("Starting %s on %s\n", SKETCHNAME, UARTA_DEVICE); uartADriver.set_device_path(device);
printf("Starting %s on %s\n", SKETCHNAME, device);
thread_should_exit = false; thread_running = true;
daemon_task = task_spawn(SKETCHNAME, thread_should_exit = false;
SCHED_RR, daemon_task = task_spawn(SKETCHNAME,
SCHED_PRIORITY_DEFAULT, SCHED_RR,
4096, SCHED_PRIORITY_DEFAULT,
main_loop, 4096,
NULL); main_loop,
exit(0); NULL);
} exit(0);
}
if (strcmp(argv[1], "stop") == 0) { if (strcmp(argv[i], "stop") == 0) {
thread_should_exit = true; thread_should_exit = true;
exit(0); exit(0);
} }
if (strcmp(argv[1], "status") == 0) { if (strcmp(argv[i], "status") == 0) {
if (thread_running) { if (thread_running) {
printf("\t%s is running\n", SKETCHNAME); printf("\t%s is running\n", SKETCHNAME);
} else { } else {
printf("\t%s is not started\n", SKETCHNAME); printf("\t%s is not started\n", SKETCHNAME);
}
exit(0);
}
if (strcmp(argv[i], "-d") == 0) {
// set terminal device
if (argc > i + 1) {
device = strdup(argv[i+1]);
} else {
printf("missing parameter to -d DEVICE\n");
usage();
exit(1);
}
} }
exit(0); }
}
printf("%s: unrecognized command ('start', 'stop' or 'status')", SKETCHNAME); usage();
exit(1); exit(1);
} }

View File

@ -36,6 +36,10 @@ public:
bool _initialised; bool _initialised;
void set_device_path(const char *path) {
_devpath = path;
}
private: private:
const char *_devpath; const char *_devpath;
int _fd; int _fd;