aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-07 13:04:49 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-07 13:04:49 +0200
commitebc12eebd0d2606bb2b9f51fd9edb058b65b18b4 (patch)
tree5f0194abf19e999456dc3f098477f8c2a7682b1b
parent34b6a91860e2925cfb7dbce4e3ce5b5a12c73e94 (diff)
parent5c74809dac57f58f92ad92433496731481703982 (diff)
downloadpx4-firmware-ebc12eebd0d2606bb2b9f51fd9edb058b65b18b4.tar.gz
px4-firmware-ebc12eebd0d2606bb2b9f51fd9edb058b65b18b4.tar.bz2
px4-firmware-ebc12eebd0d2606bb2b9f51fd9edb058b65b18b4.zip
Merged
-rw-r--r--ROMFS/px4fmu_common/mixers/IO_pass.mix38
-rw-r--r--makefiles/firmware.mk12
-rw-r--r--makefiles/nuttx.mk6
-rw-r--r--src/drivers/px4io/px4io.cpp21
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp16
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp18
-rw-r--r--src/modules/px4iofirmware/mixer.cpp18
-rw-r--r--src/systemcmds/mixer/mixer.c4
8 files changed, 101 insertions, 32 deletions
diff --git a/ROMFS/px4fmu_common/mixers/IO_pass.mix b/ROMFS/px4fmu_common/mixers/IO_pass.mix
new file mode 100644
index 000000000..39f875ddb
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/IO_pass.mix
@@ -0,0 +1,38 @@
+Passthrough mixer for PX4IO
+============================
+
+This file defines passthrough mixers suitable for testing.
+
+Channel group 0, channels 0-7 are passed directly through to the outputs.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 0 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 1 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 2 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 4 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 5 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 6 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 7 10000 10000 0 -10000 10000
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index 6b09e6ec3..f1c1b496a 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -177,6 +177,12 @@ GLOBAL_DEPS += $(MAKEFILE_LIST)
EXTRA_CLEANS =
################################################################################
+# NuttX libraries and paths
+################################################################################
+
+include $(PX4_MK_DIR)/nuttx.mk
+
+################################################################################
# Modules
################################################################################
@@ -297,12 +303,6 @@ $(LIBRARY_CLEANS):
clean
################################################################################
-# NuttX libraries and paths
-################################################################################
-
-include $(PX4_MK_DIR)/nuttx.mk
-
-################################################################################
# ROMFS generation
################################################################################
diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk
index 346735a02..d283096b2 100644
--- a/makefiles/nuttx.mk
+++ b/makefiles/nuttx.mk
@@ -69,10 +69,14 @@ INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \
LIB_DIRS += $(NUTTX_EXPORT_DIR)libs
LIBS += -lapps -lnuttx
-LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \
+NUTTX_LIBS = $(NUTTX_EXPORT_DIR)libs/libapps.a \
$(NUTTX_EXPORT_DIR)libs/libnuttx.a
+LINK_DEPS += $(NUTTX_LIBS)
$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
@$(ECHO) %% Unpacking $(NUTTX_ARCHIVE)
$(Q) $(UNZIP_CMD) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
$(Q) $(TOUCH) $@
+
+ $(LDSCRIPT): $(NUTTX_CONFIG_HEADER)
+ $(NUTTX_LIBS): $(NUTTX_CONFIG_HEADER)
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 0934e614b..19163cebe 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1302,7 +1302,7 @@ PX4IO::print_status()
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
- printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n",
+ printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n",
(double)_battery_amp_per_volt,
(double)_battery_amp_bias,
(double)_battery_mamphour_total);
@@ -1496,7 +1496,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
case MIXERIOCLOADBUF: {
const char *buf = (const char *)arg;
- ret = mixer_send(buf, strnlen(buf, 1024));
+ ret = mixer_send(buf, strnlen(buf, 2048));
break;
}
@@ -1637,6 +1637,13 @@ test(void)
if (ioctl(fd, PWM_SERVO_ARM, 0))
err(1, "failed to arm servos");
+ /* Open console directly to grab CTRL-C signal */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
for (;;) {
/* sweep all servos between 1000..2000 */
@@ -1671,6 +1678,16 @@ test(void)
if (value != servos[i])
errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
}
+
+ /* Check if user wants to quit */
+ char c;
+ if (read(console, &c, 1) == 1) {
+ if (c == 0x03 || c == 0x63) {
+ warnx("User abort\n");
+ close(console);
+ exit(0);
+ }
+ }
}
}
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 3b411031a..890184427 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -44,6 +44,7 @@
#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"
@@ -73,7 +74,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,13 +95,14 @@ 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",
+
+ deamon_task = task_spawn_cmd("att_pos_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
4096,
@@ -116,10 +118,10 @@ 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");
} else {
- printf("\tkalman_demo app not started\n");
+ warnx("not started\n");
}
exit(0);
@@ -132,7 +134,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\n");
using namespace math;
@@ -144,7 +146,7 @@ int kalman_demo_thread_main(int argc, char *argv[])
nav.update();
}
- printf("[kalman_demo] exiting.\n");
+ printf("exiting.\n");
thread_running = false;
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index e2330427d..4803a526e 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -47,6 +47,7 @@
#include <systemlib/systemlib.h>
#include <controllib/fixedwing.hpp>
#include <systemlib/param/param.h>
+#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
@@ -80,7 +81,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: control_demo {start|stop|status} [-p <additional params>]\n\n");
+ fprintf(stderr, "usage: fixedwing_backside {start|stop|status} [-p <additional params>]\n\n");
exit(1);
}
@@ -101,13 +102,14 @@ int fixedwing_backside_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("control_demo already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn_cmd("control_demo",
+
+ deamon_task = task_spawn_cmd("fixedwing_backside",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
@@ -128,10 +130,10 @@ int fixedwing_backside_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tcontrol_demo app is running\n");
+ warnx("is running");
} else {
- printf("\tcontrol_demo app not started\n");
+ warnx("not started");
}
exit(0);
@@ -144,7 +146,7 @@ int fixedwing_backside_main(int argc, char *argv[])
int control_demo_thread_main(int argc, char *argv[])
{
- printf("[control_Demo] starting\n");
+ warnx("starting");
using namespace control;
@@ -156,7 +158,7 @@ int control_demo_thread_main(int argc, char *argv[])
autopilot.update();
}
- printf("[control_demo] exiting.\n");
+ warnx("exiting.");
thread_running = false;
@@ -165,6 +167,6 @@ int control_demo_thread_main(int argc, char *argv[])
void test()
{
- printf("beginning control lib test\n");
+ warnx("beginning control lib test");
control::basicBlocksTest();
}
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 0b8ed6dc5..a2193b526 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -294,8 +294,7 @@ mixer_handle_text(const void *buffer, size_t length)
case F2I_MIXER_ACTION_APPEND:
isr_debug(2, "append %d", length);
- /* check for overflow - this is really fatal */
- /* XXX could add just what will fit & try to parse, then repeat... */
+ /* check for overflow - this would be really fatal */
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
return;
@@ -314,8 +313,13 @@ mixer_handle_text(const void *buffer, size_t length)
/* if anything was parsed */
if (resid != mixer_text_length) {
- /* ideally, this should test resid == 0 ? */
- r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ /* only set mixer ok if no residual is left over */
+ if (resid == 0) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ } else {
+ /* not yet reached the end of the mixer, set as not ok */
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
+ }
isr_debug(2, "used %u", mixer_text_length - resid);
@@ -338,11 +342,13 @@ mixer_set_failsafe()
{
/*
* Check if a custom failsafe value has been written,
- * else use the opportunity to set decent defaults.
+ * or if the mixer is not ok and bail out.
*/
- if (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
+ if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ||
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))
return;
+ /* set failsafe defaults to the values for all inputs = 0 */
float outputs[IO_SERVO_COUNT];
unsigned mixed;
diff --git a/src/systemcmds/mixer/mixer.c b/src/systemcmds/mixer/mixer.c
index 55c4f0836..e642ed067 100644
--- a/src/systemcmds/mixer/mixer.c
+++ b/src/systemcmds/mixer/mixer.c
@@ -88,8 +88,8 @@ load(const char *devname, const char *fname)
{
int dev;
FILE *fp;
- char line[80];
- char buf[512];
+ char line[120];
+ char buf[2048];
/* open the device */
if ((dev = open(devname, 0)) < 0)