aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-06-07 19:29:14 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-06-07 19:29:14 +0400
commit03357f89fddb90ddba8e1dce6f82849b7598817c (patch)
tree39df26db9846ad4c5a9e6536a5421c80518cef94
parent5bad18691649b4b50d46c11384c3aa5051b6519e (diff)
parent5c74809dac57f58f92ad92433496731481703982 (diff)
downloadpx4-firmware-03357f89fddb90ddba8e1dce6f82849b7598817c.tar.gz
px4-firmware-03357f89fddb90ddba8e1dce6f82849b7598817c.tar.bz2
px4-firmware-03357f89fddb90ddba8e1dce6f82849b7598817c.zip
Merge branch 'master' into sdlog2
-rw-r--r--ROMFS/px4fmu_common/mixers/IO_pass.mix38
-rw-r--r--makefiles/config_px4fmu_default.mk3
-rw-r--r--makefiles/firmware.mk12
-rw-r--r--makefiles/nuttx.mk6
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk12
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig8
-rw-r--r--src/drivers/hott_telemetry/hott_telemetry_main.c14
-rw-r--r--src/drivers/px4io/px4io.cpp21
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c54
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp15
-rw-r--r--src/modules/attitude_estimator_so3_comp/README5
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp833
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c63
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h44
-rw-r--r--src/modules/attitude_estimator_so3_comp/module.mk8
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp17
-rw-r--r--src/modules/gpio_led/gpio_led.c70
-rw-r--r--src/modules/px4iofirmware/mixer.cpp18
-rw-r--r--src/systemcmds/mixer/mixer.c4
19 files changed, 1155 insertions, 90 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/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk
index 53f371f90..d50eb1e50 100644
--- a/makefiles/config_px4fmu_default.mk
+++ b/makefiles/config_px4fmu_default.mk
@@ -62,7 +62,8 @@ MODULES += modules/gpio_led
# Estimation modules (EKF / other filters)
#
MODULES += modules/attitude_estimator_ekf
-MODULES += modules/position_estimator_mc
+MODULES += modules/attitude_estimator_so3_comp
+#MODULES += modules/position_estimator_mc
MODULES += modules/position_estimator
MODULES += modules/att_pos_estimator_ekf
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/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index c75a08bd1..99c2776fd 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -70,6 +70,14 @@ ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \
-march=armv7-m \
-mfloat-abi=soft
+ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions \
+ -ffixed-r10
+
+ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions \
+ -ffixed-r10
+
+ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
+
# Pick the right set of flags for the architecture.
#
ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH))
@@ -91,8 +99,8 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
# enable precise stack overflow tracking
# note - requires corresponding support in NuttX
-INSTRUMENTATIONDEFINES = -finstrument-functions \
- -ffixed-r10
+INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH))
+
# Language-specific flags
#
ARCHCFLAGS = -std=gnu99
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index 02e224302..0662f7fbe 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y
CONFIG_SERIAL_CONSOLE_REINIT=y
CONFIG_STANDARD_SERIAL=y
-CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART1_SERIAL_CONSOLE=n
CONFIG_USART2_SERIAL_CONSOLE=n
CONFIG_USART3_SERIAL_CONSOLE=n
CONFIG_UART4_SERIAL_CONSOLE=n
@@ -561,7 +561,7 @@ CONFIG_START_MONTH=1
CONFIG_START_DAY=1
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
-CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_CONSOLE=n
CONFIG_DEV_LOWCONSOLE=n
CONFIG_MUTEX_TYPES=n
CONFIG_PRIORITY_INHERITANCE=y
@@ -717,7 +717,7 @@ CONFIG_ARCH_BZERO=n
# zero for all dynamic allocations.
#
CONFIG_MAX_TASKS=32
-CONFIG_MAX_TASK_ARGS=8
+CONFIG_MAX_TASK_ARGS=10
CONFIG_NPTHREAD_KEYS=4
CONFIG_NFILE_DESCRIPTORS=32
CONFIG_NFILE_STREAMS=25
@@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512
# Size of the serial receive/transmit buffers. Default 256.
#
CONFIG_CDCACM=y
-CONFIG_CDCACM_CONSOLE=n
+CONFIG_CDCACM_CONSOLE=y
#CONFIG_CDCACM_EP0MAXPACKET
CONFIG_CDCACM_EPINTIN=1
#CONFIG_CDCACM_EPINTIN_FSSIZE
diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c
index 4318244f8..1d2bdd92e 100644
--- a/src/drivers/hott_telemetry/hott_telemetry_main.c
+++ b/src/drivers/hott_telemetry/hott_telemetry_main.c
@@ -133,15 +133,14 @@ recv_req_id(int uart, uint8_t *id)
if (poll(fds, 1, timeout_ms) > 0) {
/* Get the mode: binary or text */
read(uart, &mode, sizeof(mode));
- /* Read the device ID being polled */
- read(uart, id, sizeof(*id));
/* if we have a binary mode request */
if (mode != BINARY_MODE_REQUEST_ID) {
- warnx("Non binary request ID detected: %d", mode);
return ERROR;
}
+ /* Read the device ID being polled */
+ read(uart, id, sizeof(*id));
} else {
warnx("UART timeout on TX/RX port");
return ERROR;
@@ -216,9 +215,15 @@ hott_telemetry_thread_main(int argc, char *argv[])
uint8_t buffer[MESSAGE_BUFFER_SIZE];
size_t size = 0;
uint8_t id = 0;
+ bool connected = true;
while (!thread_should_exit) {
if (recv_req_id(uart, &id) == OK) {
+ if (!connected) {
+ connected = true;
+ warnx("OK");
+ }
+
switch (id) {
case EAM_SENSOR_ID:
build_eam_response(buffer, &size);
@@ -234,7 +239,8 @@ hott_telemetry_thread_main(int argc, char *argv[])
send_data(uart, buffer, size);
} else {
- warnx("NOK");
+ connected = false;
+ warnx("syncing");
}
}
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/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index a5d847777..c568aaadc 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * 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.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,27 +32,33 @@
****************************************************************************/
/**
- * @file px4_deamon_app.c
- * Deamon application example for PX4 autopilot
+ * @file px4_daemon_app.c
+ * daemon application example for PX4 autopilot
+ *
+ * @author Example User <mail@example.com>
*/
#include <nuttx/config.h>
+#include <nuttx/sched.h>
#include <unistd.h>
#include <stdio.h>
-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 */
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+
+static bool thread_should_exit = false; /**< daemon exit flag */
+static bool thread_running = false; /**< daemon status flag */
+static int daemon_task; /**< Handle of daemon task / thread */
/**
- * Deamon management function.
+ * daemon management function.
*/
-__EXPORT int px4_deamon_app_main(int argc, char *argv[]);
+__EXPORT int px4_daemon_app_main(int argc, char *argv[]);
/**
- * Mainloop of deamon.
+ * Mainloop of daemon.
*/
-int px4_deamon_thread_main(int argc, char *argv[]);
+int px4_daemon_thread_main(int argc, char *argv[]);
/**
* Print the correct usage.
@@ -64,20 +69,19 @@ static void
usage(const char *reason)
{
if (reason)
- fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
- exit(1);
+ warnx("%s\n", reason);
+ errx(1, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
}
/**
- * The deamon app only briefly exists to start
+ * The daemon app only briefly exists to start
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_create().
*/
-int px4_deamon_app_main(int argc, char *argv[])
+int px4_daemon_app_main(int argc, char *argv[])
{
if (argc < 1)
usage("missing command");
@@ -85,17 +89,17 @@ int px4_deamon_app_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("deamon already running\n");
+ warnx("daemon already running\n");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn("deamon",
+ daemon_task = task_spawn("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
4096,
- px4_deamon_thread_main,
+ px4_daemon_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
}
@@ -107,9 +111,9 @@ int px4_deamon_app_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tdeamon app is running\n");
+ warnx("\trunning\n");
} else {
- printf("\tdeamon app not started\n");
+ warnx("\tnot started\n");
}
exit(0);
}
@@ -118,18 +122,18 @@ int px4_deamon_app_main(int argc, char *argv[])
exit(1);
}
-int px4_deamon_thread_main(int argc, char *argv[]) {
+int px4_daemon_thread_main(int argc, char *argv[]) {
- printf("[deamon] starting\n");
+ warnx("[daemon] starting\n");
thread_running = true;
while (!thread_should_exit) {
- printf("Hello Deamon!\n");
+ warnx("Hello daemon!\n");
sleep(10);
}
- printf("[deamon] exiting.\n");
+ warnx("[daemon] exiting.\n");
thread_running = false;
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index aebe3d1fe..10592ec7c 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,13 @@ 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("kalman_demo",
+ deamon_task = task_spawn("att_pos_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
4096,
@@ -116,10 +117,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 +133,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 +145,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/attitude_estimator_so3_comp/README b/src/modules/attitude_estimator_so3_comp/README
new file mode 100644
index 000000000..79c50a531
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/README
@@ -0,0 +1,5 @@
+Synopsis
+
+ nsh> attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200
+
+Option -d is for debugging packet. See code for detailed packet structure.
diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
new file mode 100755
index 000000000..3cbc62ea1
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
@@ -0,0 +1,833 @@
+/*
+ * Author: Hyon Lim <limhyon@gmail.com, hyonlim@snu.ac.kr>
+ *
+ * @file attitude_estimator_so3_comp_main.c
+ *
+ * Implementation of nonlinear complementary filters on the SO(3).
+ * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
+ * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
+ *
+ * Theory of nonlinear complementary filters on the SO(3) is based on [1].
+ * Quaternion realization of [1] is based on [2].
+ * Optmized quaternion update code is based on Sebastian Madgwick's implementation.
+ *
+ * References
+ * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008
+ * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <poll.h>
+#include <fcntl.h>
+#include <float.h>
+#include <nuttx/sched.h>
+#include <sys/prctl.h>
+#include <termios.h>
+#include <errno.h>
+#include <limits.h>
+#include <math.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/debug_key_value.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/parameter_update.h>
+#include <drivers/drv_hrt.h>
+
+#include <systemlib/systemlib.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+#include "attitude_estimator_so3_comp_params.h"
+#ifdef __cplusplus
+}
+#endif
+
+extern "C" __EXPORT int attitude_estimator_so3_comp_main(int argc, char *argv[]);
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int attitude_estimator_so3_comp_task; /**< Handle of deamon task / thread */
+static float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */
+static float dq0 = 0.0f, dq1 = 0.0f, dq2 = 0.0f, dq3 = 0.0f; /** quaternion of sensor frame relative to auxiliary frame */
+static float gyro_bias[3] = {0.0f, 0.0f, 0.0f}; /** bias estimation */
+static bool bFilterInit = false;
+
+//! Auxiliary variables to reduce number of repeated operations
+static float q0q0, q0q1, q0q2, q0q3;
+static float q1q1, q1q2, q1q3;
+static float q2q2, q2q3;
+static float q3q3;
+
+//! Serial packet related
+static int uart;
+static int baudrate;
+
+/**
+ * Mainloop of attitude_estimator_so3_comp.
+ */
+int attitude_estimator_so3_comp_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: attitude_estimator_so3_comp {start|stop|status} [-d <devicename>] [-b <baud rate>]\n"
+ "-d and -b options are for separate visualization with raw data (quaternion packet) transfer\n"
+ "ex) attitude_estimator_so3_comp start -d /dev/ttyS1 -b 115200\n");
+ exit(1);
+}
+
+/**
+ * The attitude_estimator_so3_comp app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int attitude_estimator_so3_comp_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("attitude_estimator_so3_comp already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ attitude_estimator_so3_comp_task = task_spawn("attitude_estimator_so3_comp",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 12400,
+ attitude_estimator_so3_comp_thread_main,
+ (const char **)argv);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+
+ while(thread_running){
+ usleep(200000);
+ printf(".");
+ }
+ printf("terminated.");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ printf("\tattitude_estimator_so3_comp app is running\n");
+
+ } else {
+ printf("\tattitude_estimator_so3_comp app not started\n");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+//---------------------------------------------------------------------------------------------------
+// Fast inverse square-root
+// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
+float invSqrt(float number) {
+ volatile long i;
+ volatile float x, y;
+ volatile const float f = 1.5F;
+
+ x = number * 0.5F;
+ y = number;
+ i = * (( long * ) &y);
+ i = 0x5f375a86 - ( i >> 1 );
+ y = * (( float * ) &i);
+ y = y * ( f - ( x * y * y ) );
+ return y;
+}
+
+//! Using accelerometer, sense the gravity vector.
+//! Using magnetometer, sense yaw.
+void NonlinearSO3AHRSinit(float ax, float ay, float az, float mx, float my, float mz)
+{
+ float initialRoll, initialPitch;
+ float cosRoll, sinRoll, cosPitch, sinPitch;
+ float magX, magY;
+ float initialHdg, cosHeading, sinHeading;
+
+ initialRoll = atan2(-ay, -az);
+ initialPitch = atan2(ax, -az);
+
+ cosRoll = cosf(initialRoll);
+ sinRoll = sinf(initialRoll);
+ cosPitch = cosf(initialPitch);
+ sinPitch = sinf(initialPitch);
+
+ magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
+
+ magY = my * cosRoll - mz * sinRoll;
+
+ initialHdg = atan2f(-magY, magX);
+
+ cosRoll = cosf(initialRoll * 0.5f);
+ sinRoll = sinf(initialRoll * 0.5f);
+
+ cosPitch = cosf(initialPitch * 0.5f);
+ sinPitch = sinf(initialPitch * 0.5f);
+
+ cosHeading = cosf(initialHdg * 0.5f);
+ sinHeading = sinf(initialHdg * 0.5f);
+
+ q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
+ q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
+ q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
+ q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
+
+ // auxillary variables to reduce number of repeated operations, for 1st pass
+ q0q0 = q0 * q0;
+ q0q1 = q0 * q1;
+ q0q2 = q0 * q2;
+ q0q3 = q0 * q3;
+ q1q1 = q1 * q1;
+ q1q2 = q1 * q2;
+ q1q3 = q1 * q3;
+ q2q2 = q2 * q2;
+ q2q3 = q2 * q3;
+ q3q3 = q3 * q3;
+}
+
+void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float twoKp, float twoKi, float dt) {
+ float recipNorm;
+ float halfex = 0.0f, halfey = 0.0f, halfez = 0.0f;
+
+ //! Make filter converge to initial solution faster
+ //! This function assumes you are in static position.
+ //! WARNING : in case air reboot, this can cause problem. But this is very
+ //! unlikely happen.
+ if(bFilterInit == false)
+ {
+ NonlinearSO3AHRSinit(ax,ay,az,mx,my,mz);
+ bFilterInit = true;
+ }
+
+ //! If magnetometer measurement is available, use it.
+ if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
+ float hx, hy, hz, bx, bz;
+ float halfwx, halfwy, halfwz;
+
+ // Normalise magnetometer measurement
+ // Will sqrt work better? PX4 system is powerful enough?
+ recipNorm = invSqrt(mx * mx + my * my + mz * mz);
+ mx *= recipNorm;
+ my *= recipNorm;
+ mz *= recipNorm;
+
+ // Reference direction of Earth's magnetic field
+ hx = 2.0f * (mx * (0.5f - q2q2 - q3q3) + my * (q1q2 - q0q3) + mz * (q1q3 + q0q2));
+ hy = 2.0f * (mx * (q1q2 + q0q3) + my * (0.5f - q1q1 - q3q3) + mz * (q2q3 - q0q1));
+ hz = 2 * mx * (q1q3 - q0q2) + 2 * my * (q2q3 + q0q1) + 2 * mz * (0.5 - q1q1 - q2q2);
+ bx = sqrt(hx * hx + hy * hy);
+ bz = hz;
+
+ // Estimated direction of magnetic field
+ halfwx = bx * (0.5f - q2q2 - q3q3) + bz * (q1q3 - q0q2);
+ halfwy = bx * (q1q2 - q0q3) + bz * (q0q1 + q2q3);
+ halfwz = bx * (q0q2 + q1q3) + bz * (0.5f - q1q1 - q2q2);
+
+ // Error is sum of cross product between estimated direction and measured direction of field vectors
+ halfex += (my * halfwz - mz * halfwy);
+ halfey += (mz * halfwx - mx * halfwz);
+ halfez += (mx * halfwy - my * halfwx);
+ }
+
+ // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+ if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
+ float halfvx, halfvy, halfvz;
+
+ // Normalise accelerometer measurement
+ recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+ ax *= recipNorm;
+ ay *= recipNorm;
+ az *= recipNorm;
+
+ // Estimated direction of gravity and magnetic field
+ halfvx = q1q3 - q0q2;
+ halfvy = q0q1 + q2q3;
+ halfvz = q0q0 - 0.5f + q3q3;
+
+ // Error is sum of cross product between estimated direction and measured direction of field vectors
+ halfex += ay * halfvz - az * halfvy;
+ halfey += az * halfvx - ax * halfvz;
+ halfez += ax * halfvy - ay * halfvx;
+ }
+
+ // Apply feedback only when valid data has been gathered from the accelerometer or magnetometer
+ if(halfex != 0.0f && halfey != 0.0f && halfez != 0.0f) {
+ // Compute and apply integral feedback if enabled
+ if(twoKi > 0.0f) {
+ gyro_bias[0] += twoKi * halfex * dt; // integral error scaled by Ki
+ gyro_bias[1] += twoKi * halfey * dt;
+ gyro_bias[2] += twoKi * halfez * dt;
+ gx += gyro_bias[0]; // apply integral feedback
+ gy += gyro_bias[1];
+ gz += gyro_bias[2];
+ }
+ else {
+ gyro_bias[0] = 0.0f; // prevent integral windup
+ gyro_bias[1] = 0.0f;
+ gyro_bias[2] = 0.0f;
+ }
+
+ // Apply proportional feedback
+ gx += twoKp * halfex;
+ gy += twoKp * halfey;
+ gz += twoKp * halfez;
+ }
+
+ //! Integrate rate of change of quaternion
+#if 0
+ gx *= (0.5f * dt); // pre-multiply common factors
+ gy *= (0.5f * dt);
+ gz *= (0.5f * dt);
+#endif
+
+ // Time derivative of quaternion. q_dot = 0.5*q\otimes omega.
+ //! q_k = q_{k-1} + dt*\dot{q}
+ //! \dot{q} = 0.5*q \otimes P(\omega)
+ dq0 = 0.5f*(-q1 * gx - q2 * gy - q3 * gz);
+ dq1 = 0.5f*(q0 * gx + q2 * gz - q3 * gy);
+ dq2 = 0.5f*(q0 * gy - q1 * gz + q3 * gx);
+ dq3 = 0.5f*(q0 * gz + q1 * gy - q2 * gx);
+
+ q0 += dt*dq0;
+ q1 += dt*dq1;
+ q2 += dt*dq2;
+ q3 += dt*dq3;
+
+ // Normalise quaternion
+ recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+ q0 *= recipNorm;
+ q1 *= recipNorm;
+ q2 *= recipNorm;
+ q3 *= recipNorm;
+
+ // Auxiliary variables to avoid repeated arithmetic
+ q0q0 = q0 * q0;
+ q0q1 = q0 * q1;
+ q0q2 = q0 * q2;
+ q0q3 = q0 * q3;
+ q1q1 = q1 * q1;
+ q1q2 = q1 * q2;
+ q1q3 = q1 * q3;
+ q2q2 = q2 * q2;
+ q2q3 = q2 * q3;
+ q3q3 = q3 * q3;
+}
+
+void send_uart_byte(char c)
+{
+ write(uart,&c,1);
+}
+
+void send_uart_bytes(uint8_t *data, int length)
+{
+ write(uart,data,(size_t)(sizeof(uint8_t)*length));
+}
+
+void send_uart_float(float f) {
+ uint8_t * b = (uint8_t *) &f;
+
+ //! Assume float is 4-bytes
+ for(int i=0; i<4; i++) {
+
+ uint8_t b1 = (b[i] >> 4) & 0x0f;
+ uint8_t b2 = (b[i] & 0x0f);
+
+ uint8_t c1 = (b1 < 10) ? ('0' + b1) : 'A' + b1 - 10;
+ uint8_t c2 = (b2 < 10) ? ('0' + b2) : 'A' + b2 - 10;
+
+ send_uart_bytes(&c1,1);
+ send_uart_bytes(&c2,1);
+ }
+}
+
+void send_uart_float_arr(float *arr, int length)
+{
+ for(int i=0;i<length;++i)
+ {
+ send_uart_float(arr[i]);
+ send_uart_byte(',');
+ }
+}
+
+int open_uart(int baud, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
+{
+ int speed;
+
+ switch (baud) {
+ case 0: speed = B0; break;
+ case 50: speed = B50; break;
+ case 75: speed = B75; break;
+ case 110: speed = B110; break;
+ case 134: speed = B134; break;
+ case 150: speed = B150; break;
+ case 200: speed = B200; break;
+ case 300: speed = B300; break;
+ case 600: speed = B600; break;
+ case 1200: speed = B1200; break;
+ case 1800: speed = B1800; break;
+ case 2400: speed = B2400; break;
+ case 4800: speed = B4800; break;
+ case 9600: speed = B9600; break;
+ case 19200: speed = B19200; break;
+ case 38400: speed = B38400; break;
+ case 57600: speed = B57600; break;
+ case 115200: speed = B115200; break;
+ case 230400: speed = B230400; break;
+ case 460800: speed = B460800; break;
+ case 921600: speed = B921600; break;
+ default:
+ printf("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ return -EINVAL;
+ }
+
+ printf("[so3_comp_filt] UART is %s, baudrate is %d\n", uart_name, baud);
+ uart = open(uart_name, O_RDWR | O_NOCTTY);
+
+ /* Try to set baud rate */
+ struct termios uart_config;
+ int termios_state;
+ *is_usb = false;
+
+ /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */
+ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) {
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
+ printf("ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+ /* Fill the struct for the new configuration */
+ tcgetattr(uart, &uart_config);
+
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+
+ /* Set baud rate */
+ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
+ printf("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ printf("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ close(uart);
+ return -1;
+ }
+
+ } else {
+ *is_usb = true;
+ }
+
+ return uart;
+}
+
+/*
+ * [Rot_matrix,x_aposteriori,P_aposteriori] = attitudeKalmanfilter(dt,z_k,x_aposteriori_k,P_aposteriori_k,knownConst)
+ */
+
+/*
+ * EKF Attitude Estimator main function.
+ *
+ * Estimates the attitude recursively once started.
+ *
+ * @param argc number of commandline arguments (plus command name)
+ * @param argv strings containing the arguments
+ */
+int attitude_estimator_so3_comp_thread_main(int argc, char *argv[])
+{
+
+const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
+
+ //! Serial debug related
+ int ch;
+ struct termios uart_config_original;
+ bool usb_uart;
+ bool debug_mode = false;
+ char *device_name = "/dev/ttyS2";
+ baudrate = 115200;
+
+ //! Time constant
+ float dt = 0.005f;
+
+ /* output euler angles */
+ float euler[3] = {0.0f, 0.0f, 0.0f};
+
+ float Rot_matrix[9] = {1.f, 0, 0,
+ 0, 1.f, 0,
+ 0, 0, 1.f
+ }; /**< init: identity matrix */
+
+ float acc[3] = {0.0f, 0.0f, 0.0f};
+ float gyro[3] = {0.0f, 0.0f, 0.0f};
+ float mag[3] = {0.0f, 0.0f, 0.0f};
+
+ /* work around some stupidity in task_create's argv handling */
+ argc -= 2;
+ argv += 2;
+
+ //! -d <device_name>, default : /dev/ttyS2
+ //! -b <baud_rate>, default : 115200
+ while ((ch = getopt(argc,argv,"d:b:")) != EOF){
+ switch(ch){
+ case 'b':
+ baudrate = strtoul(optarg, NULL, 10);
+ if(baudrate == 0)
+ printf("invalid baud rate '%s'",optarg);
+ break;
+ case 'd':
+ device_name = optarg;
+ debug_mode = true;
+ break;
+ default:
+ usage("invalid argument");
+ }
+ }
+
+ if(debug_mode){
+ printf("Opening debugging port for 3D visualization\n");
+ uart = open_uart(baudrate, device_name, &uart_config_original, &usb_uart);
+ if (uart < 0)
+ printf("could not open %s", device_name);
+ else
+ printf("Open port success\n");
+ }
+
+ // print text
+ printf("Nonlinear SO3 Attitude Estimator initialized..\n\n");
+ fflush(stdout);
+
+ int overloadcounter = 19;
+
+ /* store start time to guard against too slow update rates */
+ uint64_t last_run = hrt_absolute_time();
+
+ struct sensor_combined_s raw;
+ memset(&raw, 0, sizeof(raw));
+
+ //! Initialize attitude vehicle uORB message.
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+
+ struct vehicle_status_s state;
+ memset(&state, 0, sizeof(state));
+
+ uint64_t last_data = 0;
+ uint64_t last_measurement = 0;
+
+ /* subscribe to raw data */
+ int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
+ /* rate-limit raw data updates to 200Hz */
+ orb_set_interval(sub_raw, 4);
+
+ /* subscribe to param changes */
+ int sub_params = orb_subscribe(ORB_ID(parameter_update));
+
+ /* subscribe to system state*/
+ int sub_state = orb_subscribe(ORB_ID(vehicle_status));
+
+ /* advertise attitude */
+ orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
+
+ int loopcounter = 0;
+ int printcounter = 0;
+
+ thread_running = true;
+
+ /* advertise debug value */
+ // struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
+ // orb_advert_t pub_dbg = -1;
+
+ float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
+ // XXX write this out to perf regs
+
+ /* keep track of sensor updates */
+ uint32_t sensor_last_count[3] = {0, 0, 0};
+ uint64_t sensor_last_timestamp[3] = {0, 0, 0};
+
+ struct attitude_estimator_so3_comp_params so3_comp_params;
+ struct attitude_estimator_so3_comp_param_handles so3_comp_param_handles;
+
+ /* initialize parameter handles */
+ parameters_init(&so3_comp_param_handles);
+
+ uint64_t start_time = hrt_absolute_time();
+ bool initialized = false;
+
+ float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
+ unsigned offset_count = 0;
+
+ /* register the perf counter */
+ perf_counter_t so3_comp_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_so3_comp");
+
+ /* Main loop*/
+ while (!thread_should_exit) {
+
+ struct pollfd fds[2];
+ fds[0].fd = sub_raw;
+ fds[0].events = POLLIN;
+ fds[1].fd = sub_params;
+ fds[1].events = POLLIN;
+ int ret = poll(fds, 2, 1000);
+
+ if (ret < 0) {
+ /* XXX this is seriously bad - should be an emergency */
+ } else if (ret == 0) {
+ /* check if we're in HIL - not getting sensor data is fine then */
+ orb_copy(ORB_ID(vehicle_status), sub_state, &state);
+
+ if (!state.flag_hil_enabled) {
+ fprintf(stderr,
+ "[att so3_comp] WARNING: Not getting sensors - sensor app running?\n");
+ }
+
+ } else {
+
+ /* only update parameters if they changed */
+ if (fds[1].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), sub_params, &update);
+
+ /* update parameters */
+ parameters_update(&so3_comp_param_handles, &so3_comp_params);
+ }
+
+ /* only run filter if sensor values changed */
+ if (fds[0].revents & POLLIN) {
+
+ /* get latest measurements */
+ orb_copy(ORB_ID(sensor_combined), sub_raw, &raw);
+
+ if (!initialized) {
+
+ gyro_offsets[0] += raw.gyro_rad_s[0];
+ gyro_offsets[1] += raw.gyro_rad_s[1];
+ gyro_offsets[2] += raw.gyro_rad_s[2];
+ offset_count++;
+
+ if (hrt_absolute_time() - start_time > 3000000LL) {
+ initialized = true;
+ gyro_offsets[0] /= offset_count;
+ gyro_offsets[1] /= offset_count;
+ gyro_offsets[2] /= offset_count;
+ }
+
+ } else {
+
+ perf_begin(so3_comp_loop_perf);
+
+ /* Calculate data time difference in seconds */
+ dt = (raw.timestamp - last_measurement) / 1000000.0f;
+ last_measurement = raw.timestamp;
+ uint8_t update_vect[3] = {0, 0, 0};
+
+ /* Fill in gyro measurements */
+ if (sensor_last_count[0] != raw.gyro_counter) {
+ update_vect[0] = 1;
+ sensor_last_count[0] = raw.gyro_counter;
+ sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
+ sensor_last_timestamp[0] = raw.timestamp;
+ }
+
+ gyro[0] = raw.gyro_rad_s[0] - gyro_offsets[0];
+ gyro[1] = raw.gyro_rad_s[1] - gyro_offsets[1];
+ gyro[2] = raw.gyro_rad_s[2] - gyro_offsets[2];
+
+ /* update accelerometer measurements */
+ if (sensor_last_count[1] != raw.accelerometer_counter) {
+ update_vect[1] = 1;
+ sensor_last_count[1] = raw.accelerometer_counter;
+ sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
+ sensor_last_timestamp[1] = raw.timestamp;
+ }
+
+ acc[0] = raw.accelerometer_m_s2[0];
+ acc[1] = raw.accelerometer_m_s2[1];
+ acc[2] = raw.accelerometer_m_s2[2];
+
+ /* update magnetometer measurements */
+ if (sensor_last_count[2] != raw.magnetometer_counter) {
+ update_vect[2] = 1;
+ sensor_last_count[2] = raw.magnetometer_counter;
+ sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
+ sensor_last_timestamp[2] = raw.timestamp;
+ }
+
+ mag[0] = raw.magnetometer_ga[0];
+ mag[1] = raw.magnetometer_ga[1];
+ mag[2] = raw.magnetometer_ga[2];
+
+ uint64_t now = hrt_absolute_time();
+ unsigned int time_elapsed = now - last_run;
+ last_run = now;
+
+ if (time_elapsed > loop_interval_alarm) {
+ //TODO: add warning, cpu overload here
+ // if (overloadcounter == 20) {
+ // printf("CPU OVERLOAD DETECTED IN ATTITUDE ESTIMATOR EKF (%lu > %lu)\n", time_elapsed, loop_interval_alarm);
+ // overloadcounter = 0;
+ // }
+
+ overloadcounter++;
+ }
+
+ static bool const_initialized = false;
+
+ /* initialize with good values once we have a reasonable dt estimate */
+ if (!const_initialized && dt < 0.05f && dt > 0.005f) {
+ dt = 0.005f;
+ parameters_update(&so3_comp_param_handles, &so3_comp_params);
+ const_initialized = true;
+ }
+
+ /* do not execute the filter if not initialized */
+ if (!const_initialized) {
+ continue;
+ }
+
+ uint64_t timing_start = hrt_absolute_time();
+
+ // NOTE : Accelerometer is reversed.
+ // Because proper mount of PX4 will give you a reversed accelerometer readings.
+ NonlinearSO3AHRSupdate(gyro[0],gyro[1],gyro[2],-acc[0],-acc[1],-acc[2],mag[0],mag[1],mag[2],so3_comp_params.Kp,so3_comp_params.Ki, dt);
+
+ // Convert q->R.
+ Rot_matrix[0] = q0q0 + q1q1 - q2q2 - q3q3;// 11
+ Rot_matrix[1] = 2.0 * (q1*q2 + q0*q3); // 12
+ Rot_matrix[2] = 2.0 * (q1*q3 - q0*q2); // 13
+ Rot_matrix[3] = 2.0 * (q1*q2 - q0*q3); // 21
+ Rot_matrix[4] = q0q0 - q1q1 + q2q2 - q3q3;// 22
+ Rot_matrix[5] = 2.0 * (q2*q3 + q0*q1); // 23
+ Rot_matrix[6] = 2.0 * (q1*q3 + q0*q2); // 31
+ Rot_matrix[7] = 2.0 * (q2*q3 - q0*q1); // 32
+ Rot_matrix[8] = q0q0 - q1q1 - q2q2 + q3q3;// 33
+
+ //1-2-3 Representation.
+ //Equation (290)
+ //Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors, James Diebel.
+ // Existing PX4 EKF code was generated by MATLAB which uses coloum major order matrix.
+ euler[0] = atan2f(Rot_matrix[5], Rot_matrix[8]); //! Roll
+ euler[1] = -asinf(Rot_matrix[2]); //! Pitch
+ euler[2] = atan2f(Rot_matrix[1],Rot_matrix[0]); //! Yaw
+
+ /* swap values for next iteration, check for fatal inputs */
+ if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) {
+ /* Do something */
+ } else {
+ /* due to inputs or numerical failure the output is invalid, skip it */
+ continue;
+ }
+
+ if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator so3_comp] sensor data missed! (%llu)\n", raw.timestamp - last_data);
+
+ last_data = raw.timestamp;
+
+ /* send out */
+ att.timestamp = raw.timestamp;
+
+ // XXX Apply the same transformation to the rotation matrix
+ att.roll = euler[0] - so3_comp_params.roll_off;
+ att.pitch = euler[1] - so3_comp_params.pitch_off;
+ att.yaw = euler[2] - so3_comp_params.yaw_off;
+
+ //! Euler angle rate. But it needs to be investigated again.
+ /*
+ att.rollspeed = 2.0f*(-q1*dq0 + q0*dq1 - q3*dq2 + q2*dq3);
+ att.pitchspeed = 2.0f*(-q2*dq0 + q3*dq1 + q0*dq2 - q1*dq3);
+ att.yawspeed = 2.0f*(-q3*dq0 -q2*dq1 + q1*dq2 + q0*dq3);
+ */
+ att.rollspeed = gyro[0];
+ att.pitchspeed = gyro[1];
+ att.yawspeed = gyro[2];
+
+ att.rollacc = 0;
+ att.pitchacc = 0;
+ att.yawacc = 0;
+
+ //! Quaternion
+ att.q[0] = q0;
+ att.q[1] = q1;
+ att.q[2] = q2;
+ att.q[3] = q3;
+ att.q_valid = true;
+
+ /* TODO: Bias estimation required */
+ memcpy(&att.rate_offsets, &(gyro_bias), sizeof(att.rate_offsets));
+
+ /* copy rotation matrix */
+ memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix));
+ att.R_valid = true;
+
+ if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) {
+ // Broadcast
+ orb_publish(ORB_ID(vehicle_attitude), pub_att, &att);
+
+ } else {
+ warnx("NaN in roll/pitch/yaw estimate!");
+ }
+
+ perf_end(so3_comp_loop_perf);
+
+ //! This will print out debug packet to visualization software
+ if(debug_mode)
+ {
+ float quat[4];
+ quat[0] = q0;
+ quat[1] = q1;
+ quat[2] = q2;
+ quat[3] = q3;
+ send_uart_float_arr(quat,4);
+ send_uart_byte('\n');
+ }
+ }
+ }
+ }
+
+ loopcounter++;
+ }// while
+
+ thread_running = false;
+
+ /* Reset the UART flags to original state */
+ if (!usb_uart)
+ tcsetattr(uart, TCSANOW, &uart_config_original);
+
+ return 0;
+}
diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c
new file mode 100755
index 000000000..f962515df
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c
@@ -0,0 +1,63 @@
+/*
+ * Author: Hyon Lim <limhyon@gmail.com, hyonlim@snu.ac.kr>
+ *
+ * @file attitude_estimator_so3_comp_params.c
+ *
+ * Implementation of nonlinear complementary filters on the SO(3).
+ * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
+ * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
+ *
+ * Theory of nonlinear complementary filters on the SO(3) is based on [1].
+ * Quaternion realization of [1] is based on [2].
+ * Optmized quaternion update code is based on Sebastian Madgwick's implementation.
+ *
+ * References
+ * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008
+ * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
+ */
+
+#include "attitude_estimator_so3_comp_params.h"
+
+/* This is filter gain for nonlinear SO3 complementary filter */
+/* NOTE : How to tune the gain? First of all, stick with this default gain. And let the quad in stable place.
+ Log the steady state reponse of filter. If it is too slow, increase SO3_COMP_KP.
+ If you are flying from ground to high altitude in short amount of time, please increase SO3_COMP_KI which
+ will compensate gyro bias which depends on temperature and vibration of your vehicle */
+PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f); //! This parameter will give you about 15 seconds convergence time.
+ //! You can set this gain higher if you want more fast response.
+ //! But note that higher gain will give you also higher overshoot.
+PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.05f); //! This gain will incorporate slow time-varying bias (e.g., temperature change)
+ //! This gain is depend on your vehicle status.
+
+/* offsets in roll, pitch and yaw of sensor plane and body */
+PARAM_DEFINE_FLOAT(ATT_ROLL_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_PITCH_OFFS, 0.0f);
+PARAM_DEFINE_FLOAT(ATT_YAW_OFFS, 0.0f);
+
+int parameters_init(struct attitude_estimator_so3_comp_param_handles *h)
+{
+ /* Filter gain parameters */
+ h->Kp = param_find("SO3_COMP_KP");
+ h->Ki = param_find("SO3_COMP_KI");
+
+ /* Attitude offset (WARNING: Do not change if you do not know what exactly this variable wil lchange) */
+ h->roll_off = param_find("ATT_ROLL_OFFS");
+ h->pitch_off = param_find("ATT_PITCH_OFFS");
+ h->yaw_off = param_find("ATT_YAW_OFFS");
+
+ return OK;
+}
+
+int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p)
+{
+ /* Update filter gain */
+ param_get(h->Kp, &(p->Kp));
+ param_get(h->Ki, &(p->Ki));
+
+ /* Update attitude offset */
+ param_get(h->roll_off, &(p->roll_off));
+ param_get(h->pitch_off, &(p->pitch_off));
+ param_get(h->yaw_off, &(p->yaw_off));
+
+ return OK;
+}
diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h
new file mode 100755
index 000000000..f00695630
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h
@@ -0,0 +1,44 @@
+/*
+ * Author: Hyon Lim <limhyon@gmail.com, hyonlim@snu.ac.kr>
+ *
+ * @file attitude_estimator_so3_comp_params.h
+ *
+ * Implementation of nonlinear complementary filters on the SO(3).
+ * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
+ * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
+ *
+ * Theory of nonlinear complementary filters on the SO(3) is based on [1].
+ * Quaternion realization of [1] is based on [2].
+ * Optmized quaternion update code is based on Sebastian Madgwick's implementation.
+ *
+ * References
+ * [1] Mahony, R.; Hamel, T.; Pflimlin, Jean-Michel, "Nonlinear Complementary Filters on the Special Orthogonal Group," Automatic Control, IEEE Transactions on , vol.53, no.5, pp.1203,1218, June 2008
+ * [2] Euston, M.; Coote, P.; Mahony, R.; Jonghyuk Kim; Hamel, T., "A complementary filter for attitude estimation of a fixed-wing UAV," Intelligent Robots and Systems, 2008. IROS 2008. IEEE/RSJ International Conference on , vol., no., pp.340,345, 22-26 Sept. 2008
+ */
+
+#include <systemlib/param/param.h>
+
+struct attitude_estimator_so3_comp_params {
+ float Kp;
+ float Ki;
+ float roll_off;
+ float pitch_off;
+ float yaw_off;
+};
+
+struct attitude_estimator_so3_comp_param_handles {
+ param_t Kp, Ki;
+ param_t roll_off, pitch_off, yaw_off;
+};
+
+/**
+ * Initialize all parameter handles and values
+ *
+ */
+int parameters_init(struct attitude_estimator_so3_comp_param_handles *h);
+
+/**
+ * Update all parameters
+ *
+ */
+int parameters_update(const struct attitude_estimator_so3_comp_param_handles *h, struct attitude_estimator_so3_comp_params *p);
diff --git a/src/modules/attitude_estimator_so3_comp/module.mk b/src/modules/attitude_estimator_so3_comp/module.mk
new file mode 100644
index 000000000..92f43d920
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/module.mk
@@ -0,0 +1,8 @@
+#
+# Attitude estimator (Nonlinear SO3 complementary Filter)
+#
+
+MODULE_COMMAND = attitude_estimator_so3_comp
+
+SRCS = attitude_estimator_so3_comp_main.cpp \
+ attitude_estimator_so3_comp_params.c
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index e21990c92..c3d57a85a 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,13 @@ 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("control_demo",
+ deamon_task = task_spawn("fixedwing_backside",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
@@ -128,10 +129,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 +145,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 +157,7 @@ int control_demo_thread_main(int argc, char *argv[])
autopilot.update();
}
- printf("[control_demo] exiting.\n");
+ warnx("exiting.");
thread_running = false;
@@ -165,6 +166,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/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index a80bf9cb8..43cbe74c7 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -48,6 +48,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <poll.h>
@@ -64,6 +65,7 @@ struct gpio_led_s {
};
static struct gpio_led_s gpio_led_data;
+static bool gpio_led_started = false;
__EXPORT int gpio_led_main(int argc, char *argv[]);
@@ -75,31 +77,54 @@ int gpio_led_main(int argc, char *argv[])
{
int pin = GPIO_EXT_1;
- if (argc > 1) {
- if (!strcmp(argv[1], "-p")) {
- if (!strcmp(argv[2], "1")) {
- pin = GPIO_EXT_1;
+ if (argc < 2) {
+ errx(1, "no argument provided. Try 'start' or 'stop' [-p 1/2]");
- } else if (!strcmp(argv[2], "2")) {
- pin = GPIO_EXT_2;
+ } else {
- } else {
- printf("[gpio_led] Unsupported pin: %s\n", argv[2]);
+ /* START COMMAND HANDLING */
+ if (!strcmp(argv[1], "start")) {
+
+ if (argc > 2) {
+ if (!strcmp(argv[1], "-p")) {
+ if (!strcmp(argv[2], "1")) {
+ pin = GPIO_EXT_1;
+
+ } else if (!strcmp(argv[2], "2")) {
+ pin = GPIO_EXT_2;
+
+ } else {
+ warnx("[gpio_led] Unsupported pin: %s\n", argv[2]);
+ exit(1);
+ }
+ }
+ }
+
+ memset(&gpio_led_data, 0, sizeof(gpio_led_data));
+ gpio_led_data.pin = pin;
+ int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+
+ if (ret != 0) {
+ warnx("[gpio_led] Failed to queue work: %d\n", ret);
exit(1);
+
+ } else {
+ gpio_led_started = true;
}
- }
- }
- memset(&gpio_led_data, 0, sizeof(gpio_led_data));
- gpio_led_data.pin = pin;
- int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+ exit(0);
- if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
- exit(1);
- }
+ /* STOP COMMAND HANDLING */
+
+ } else if (!strcmp(argv[1], "stop")) {
+ gpio_led_started = false;
- exit(0);
+ /* INVALID COMMAND */
+
+ } else {
+ errx(1, "unrecognized command '%s', only supporting 'start' or 'stop'", argv[1]);
+ }
+ }
}
void gpio_led_start(FAR void *arg)
@@ -110,7 +135,7 @@ void gpio_led_start(FAR void *arg)
priv->gpio_fd = open(GPIO_DEVICE_PATH, 0);
if (priv->gpio_fd < 0) {
- printf("[gpio_led] GPIO: open fail\n");
+ warnx("[gpio_led] GPIO: open fail\n");
return;
}
@@ -125,11 +150,11 @@ void gpio_led_start(FAR void *arg)
int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0);
if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
+ warnx("[gpio_led] Failed to queue work: %d\n", ret);
return;
}
- printf("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
+ warnx("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
}
void gpio_led_cycle(FAR void *arg)
@@ -187,5 +212,6 @@ void gpio_led_cycle(FAR void *arg)
priv->counter = 0;
/* repeat cycle at 5 Hz*/
- work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
+ if (gpio_led_started)
+ work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
}
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)