aboutsummaryrefslogtreecommitdiff
path: root/src/modules/att_pos_estimator_ekf/kalman_main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/att_pos_estimator_ekf/kalman_main.cpp')
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp33
1 files changed, 19 insertions, 14 deletions
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 3b411031a..372b2d162 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: James Goppert
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,8 +33,10 @@
****************************************************************************/
/**
- * @file kalman_demo.cpp
- * Demonstration of control library
+ * @file kalman_main.cpp
+ * Combined attitude / position estimator.
+ *
+ * @author James Goppert
*/
#include <nuttx/config.h>
@@ -44,13 +46,14 @@
#include <string.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include "KalmanNav.hpp"
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
+static int daemon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
@@ -73,7 +76,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: kalman_demo {start|stop|status} [-p <additional params>]\n\n");
+ warnx("usage: att_pos_estimator_ekf {start|stop|status} [-p <additional params>]");
exit(1);
}
@@ -94,15 +97,16 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("kalman_demo already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn_cmd("kalman_demo",
+
+ daemon_task = task_spawn_cmd("att_pos_estimator_ekf",
SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
+ SCHED_PRIORITY_MAX - 30,
4096,
kalman_demo_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -116,13 +120,14 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tkalman_demo app is running\n");
+ warnx("is running\n");
+ exit(0);
} else {
- printf("\tkalman_demo app not started\n");
+ warnx("not started\n");
+ exit(1);
}
- exit(0);
}
usage("unrecognized command");
@@ -132,7 +137,7 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
int kalman_demo_thread_main(int argc, char *argv[])
{
- printf("[kalman_demo] starting\n");
+ warnx("starting");
using namespace math;
@@ -144,7 +149,7 @@ int kalman_demo_thread_main(int argc, char *argv[])
nav.update();
}
- printf("[kalman_demo] exiting.\n");
+ warnx("exiting.");
thread_running = false;