aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-10 15:01:44 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-10 15:01:44 +0200
commit9444def5f861745da2716a443026e3d0bf061161 (patch)
treeb25a9429d78fab148debc9e1f2d31f6d3a0afd54 /src/modules
parent308ec6001a2e1ac31ea818b1d482a34b8ed0099b (diff)
parent42ce3112ad645e53788463180c350279b243b02e (diff)
downloadpx4-firmware-9444def5f861745da2716a443026e3d0bf061161.tar.gz
px4-firmware-9444def5f861745da2716a443026e3d0bf061161.tar.bz2
px4-firmware-9444def5f861745da2716a443026e3d0bf061161.zip
Merge branch 'master' into fmuv2_bringup
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp4
-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.c217
-rw-r--r--src/modules/gpio_led/module.mk39
-rw-r--r--src/modules/mavlink/mavlink_receiver.c10
-rw-r--r--src/modules/px4iofirmware/mixer.cpp80
-rw-r--r--src/modules/px4iofirmware/protocol.h4
-rw-r--r--src/modules/px4iofirmware/registers.c10
-rw-r--r--src/modules/sdlog2/logbuffer.c134
-rw-r--r--src/modules/sdlog2/logbuffer.h68
-rw-r--r--src/modules/sdlog2/module.mk43
-rw-r--r--src/modules/sdlog2/sdlog2.c1178
-rw-r--r--src/modules/sdlog2/sdlog2_format.h98
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h191
-rw-r--r--src/modules/systemlib/geo/geo.c5
-rw-r--r--src/modules/systemlib/geo/geo.h16
22 files changed, 3045 insertions, 37 deletions
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index 4ef150da1..c3836bdfa 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
@@ -683,7 +683,8 @@ int KalmanNav::correctPos()
// fault detetcion
float beta = y.dot(S.inverse() * y);
- if (beta > _faultPos.get()) {
+ static int counter = 0;
+ if (beta > _faultPos.get() && (counter % 10 == 0)) {
printf("fault in gps: beta = %8.4f\n", (double)beta);
printf("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
double(y(0) / sqrtf(RPos(0, 0))),
@@ -693,6 +694,7 @@ int KalmanNav::correctPos()
double(y(4) / sqrtf(RPos(4, 4))),
double(y(5) / sqrtf(RPos(5, 5))));
}
+ counter++;
return ret_ok;
}
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
new file mode 100644
index 000000000..43cbe74c7
--- /dev/null
+++ b/src/modules/gpio_led/gpio_led.c
@@ -0,0 +1,217 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gpio_led.c
+ *
+ * Status LED via GPIO driver.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <fcntl.h>
+#include <stdbool.h>
+#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>
+#include <drivers/drv_gpio.h>
+
+struct gpio_led_s {
+ struct work_s work;
+ int gpio_fd;
+ int pin;
+ struct vehicle_status_s status;
+ int vehicle_status_sub;
+ bool led_state;
+ int counter;
+};
+
+static struct gpio_led_s gpio_led_data;
+static bool gpio_led_started = false;
+
+__EXPORT int gpio_led_main(int argc, char *argv[]);
+
+void gpio_led_start(FAR void *arg);
+
+void gpio_led_cycle(FAR void *arg);
+
+int gpio_led_main(int argc, char *argv[])
+{
+ int pin = GPIO_EXT_1;
+
+ if (argc < 2) {
+ errx(1, "no argument provided. Try 'start' or 'stop' [-p 1/2]");
+
+ } else {
+
+ /* 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;
+ }
+
+ exit(0);
+
+ /* STOP COMMAND HANDLING */
+
+ } else if (!strcmp(argv[1], "stop")) {
+ gpio_led_started = false;
+
+ /* INVALID COMMAND */
+
+ } else {
+ errx(1, "unrecognized command '%s', only supporting 'start' or 'stop'", argv[1]);
+ }
+ }
+}
+
+void gpio_led_start(FAR void *arg)
+{
+ FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg;
+
+ /* open GPIO device */
+ priv->gpio_fd = open(GPIO_DEVICE_PATH, 0);
+
+ if (priv->gpio_fd < 0) {
+ warnx("[gpio_led] GPIO: open fail\n");
+ return;
+ }
+
+ /* configure GPIO pin */
+ ioctl(priv->gpio_fd, GPIO_SET_OUTPUT, priv->pin);
+
+ /* subscribe to vehicle status topic */
+ memset(&priv->status, 0, sizeof(priv->status));
+ priv->vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+
+ /* add worker to queue */
+ int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0);
+
+ if (ret != 0) {
+ warnx("[gpio_led] Failed to queue work: %d\n", ret);
+ return;
+ }
+
+ warnx("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
+}
+
+void gpio_led_cycle(FAR void *arg)
+{
+ FAR struct gpio_led_s *priv = (FAR struct gpio_led_s *)arg;
+
+ /* check for status updates*/
+ bool status_updated;
+ orb_check(priv->vehicle_status_sub, &status_updated);
+
+ if (status_updated)
+ orb_copy(ORB_ID(vehicle_status), priv->vehicle_status_sub, &priv->status);
+
+ /* select pattern for current status */
+ int pattern = 0;
+
+ if (priv->status.flag_system_armed) {
+ if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
+ pattern = 0x3f; // ****** solid (armed)
+
+ } else {
+ pattern = 0x2A; // *_*_*_ fast blink (armed, battery warning)
+ }
+
+ } else {
+ if (priv->status.state_machine == SYSTEM_STATE_PREFLIGHT) {
+ pattern = 0x00; // ______ off (disarmed, preflight check)
+
+ } else if (priv->status.state_machine == SYSTEM_STATE_STANDBY &&
+ priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE) {
+ pattern = 0x38; // ***___ slow blink (disarmed, ready)
+
+ } else {
+ pattern = 0x28; // *_*___ slow double blink (disarmed, not good to arm)
+ }
+ }
+
+ /* blink pattern */
+ bool led_state_new = (pattern & (1 << priv->counter)) != 0;
+
+ if (led_state_new != priv->led_state) {
+ priv->led_state = led_state_new;
+
+ if (led_state_new) {
+ ioctl(priv->gpio_fd, GPIO_SET, priv->pin);
+
+ } else {
+ ioctl(priv->gpio_fd, GPIO_CLEAR, priv->pin);
+ }
+ }
+
+ priv->counter++;
+
+ if (priv->counter > 5)
+ priv->counter = 0;
+
+ /* repeat cycle at 5 Hz*/
+ if (gpio_led_started)
+ work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
+}
diff --git a/src/modules/gpio_led/module.mk b/src/modules/gpio_led/module.mk
new file mode 100644
index 000000000..3b8553489
--- /dev/null
+++ b/src/modules/gpio_led/module.mk
@@ -0,0 +1,39 @@
+############################################################################
+#
+# Copyright (C) 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
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Status LED via GPIO driver
+#
+
+MODULE_COMMAND = gpio_led
+SRCS = gpio_led.c
diff --git a/src/modules/mavlink/mavlink_receiver.c b/src/modules/mavlink/mavlink_receiver.c
index a42612f9e..940d030b2 100644
--- a/src/modules/mavlink/mavlink_receiver.c
+++ b/src/modules/mavlink/mavlink_receiver.c
@@ -429,11 +429,11 @@ handle_message(mavlink_message_t *msg)
hil_frames += 1 ;
// output
- if ((timestamp - old_timestamp) > 10000000) {
- printf("receiving hil gps at %d hz\n", hil_frames/10);
- old_timestamp = timestamp;
- hil_frames = 0;
- }
+ // if ((timestamp - old_timestamp) > 10000000) {
+ // printf("receiving hil gps at %d hz\n", hil_frames/10);
+ // old_timestamp = timestamp;
+ // hil_frames = 0;
+ // }
}
if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) {
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 1234e2eea..a2193b526 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -85,6 +85,9 @@ static int mixer_callback(uintptr_t handle,
static MixerGroup mixer_group(mixer_callback, 0);
+/* Set the failsafe values of all mixed channels (based on zero throttle, controls centered) */
+static void mixer_set_failsafe();
+
void
mixer_tick(void)
{
@@ -102,13 +105,16 @@ mixer_tick(void)
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
}
+ /* default to failsafe mixing */
source = MIX_FAILSAFE;
/*
* Decide which set of controls we're using.
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ||
- !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
+
+ /* do not mix if mixer is invalid or if RAW_PWM mode is on and FMU is good */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
/* don't actually mix anything - we already have raw PWM values or
not a valid mixer. */
@@ -117,6 +123,7 @@ mixer_tick(void)
} else {
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
/* mix from FMU controls */
@@ -133,14 +140,28 @@ mixer_tick(void)
}
/*
+ * Set failsafe status flag depending on mixing source
+ */
+ if (source == MIX_FAILSAFE) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
+ } else {
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
+ }
+
+ /*
* Run the mixers.
*/
if (source == MIX_FAILSAFE) {
/* copy failsafe values to the servo outputs */
- for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ for (unsigned i = 0; i < IO_SERVO_COUNT; i++) {
r_page_servos[i] = r_page_servo_failsafe[i];
+ /* safe actuators for FMU feedback */
+ r_page_actuators[i] = (r_page_servos[i] - 1500) / 600.0f;
+ }
+
+
} else if (source != MIX_NONE) {
float outputs[IO_SERVO_COUNT];
@@ -156,7 +177,7 @@ mixer_tick(void)
r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
/* scale to servo output */
- r_page_servos[i] = (outputs[i] * 500.0f) + 1500;
+ r_page_servos[i] = (outputs[i] * 600.0f) + 1500;
}
for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
@@ -175,7 +196,7 @@ mixer_tick(void)
bool should_arm = (
/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
/* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
- /* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
+ /* there is valid input via direct PWM or mixer */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) &&
/* FMU is available or FMU is not available but override is an option */
((r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) || (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ))
@@ -225,7 +246,7 @@ mixer_callback(uintptr_t handle,
case MIX_FAILSAFE:
case MIX_NONE:
- /* XXX we could allow for configuration of per-output failsafe values */
+ control = 0.0f;
return -1;
}
@@ -273,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;
@@ -293,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);
@@ -303,8 +328,43 @@ mixer_handle_text(const void *buffer, size_t length)
memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid);
mixer_text_length = resid;
+
+ /* update failsafe values */
+ mixer_set_failsafe();
}
break;
}
}
+
+static void
+mixer_set_failsafe()
+{
+ /*
+ * Check if a custom failsafe value has been written,
+ * or if the mixer is not ok and bail out.
+ */
+ 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;
+
+ /* mix */
+ mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT);
+
+ /* scale to PWM and update the servo outputs as required */
+ for (unsigned i = 0; i < mixed; i++) {
+
+ /* scale to servo output */
+ r_page_servo_failsafe[i] = (outputs[i] * 600.0f) + 1500;
+
+ }
+
+ /* disable the rest of the outputs */
+ for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
+ r_page_servo_failsafe[i] = 0;
+
+}
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 6cdf86b2b..90d63ea1a 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -111,7 +111,7 @@
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
-#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* harcoded # of relay outputs */
+#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
/* dynamic status page */
#define PX4IO_PAGE_STATUS 1
@@ -130,6 +130,7 @@
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
+#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */
@@ -174,6 +175,7 @@
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
+#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 9698a0f2f..df7d6dcd3 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -41,6 +41,7 @@
#include <stdbool.h>
#include <stdlib.h>
+#include <string.h>
#include <drivers/drv_hrt.h>
@@ -178,8 +179,10 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE
* PAGE 105
*
* Failsafe servo PWM values
+ *
+ * Disable pulses as default.
*/
-uint16_t r_page_servo_failsafe[IO_SERVO_COUNT];
+uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 0 };
void
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
@@ -230,11 +233,14 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
case PX4IO_PAGE_FAILSAFE_PWM:
/* copy channel data */
- while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
+ while ((offset < IO_SERVO_COUNT) && (num_values > 0)) {
/* XXX range-check value? */
r_page_servo_failsafe[offset] = *values;
+ /* flag the failsafe values as custom */
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM;
+
offset++;
num_values--;
values++;
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
new file mode 100644
index 000000000..8aaafaf31
--- /dev/null
+++ b/src/modules/sdlog2/logbuffer.c
@@ -0,0 +1,134 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file logbuffer.c
+ *
+ * Ring FIFO buffer for binary log data.
+ *
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+
+#include "logbuffer.h"
+
+int logbuffer_init(struct logbuffer_s *lb, int size)
+{
+ lb->size = size;
+ lb->write_ptr = 0;
+ lb->read_ptr = 0;
+ lb->data = malloc(lb->size);
+ return (lb->data == 0) ? ERROR : OK;
+}
+
+int logbuffer_count(struct logbuffer_s *lb)
+{
+ int n = lb->write_ptr - lb->read_ptr;
+
+ if (n < 0) {
+ n += lb->size;
+ }
+
+ return n;
+}
+
+int logbuffer_is_empty(struct logbuffer_s *lb)
+{
+ return lb->read_ptr == lb->write_ptr;
+}
+
+bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size)
+{
+ // bytes available to write
+ int available = lb->read_ptr - lb->write_ptr - 1;
+
+ if (available < 0)
+ available += lb->size;
+
+ if (size > available) {
+ // buffer overflow
+ return false;
+ }
+
+ char *c = (char *) ptr;
+ int n = lb->size - lb->write_ptr; // bytes to end of the buffer
+
+ if (n < size) {
+ // message goes over end of the buffer
+ memcpy(&(lb->data[lb->write_ptr]), c, n);
+ lb->write_ptr = 0;
+
+ } else {
+ n = 0;
+ }
+
+ // now: n = bytes already written
+ int p = size - n; // number of bytes to write
+ memcpy(&(lb->data[lb->write_ptr]), &(c[n]), p);
+ lb->write_ptr = (lb->write_ptr + p) % lb->size;
+ return true;
+}
+
+int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part)
+{
+ // bytes available to read
+ int available = lb->write_ptr - lb->read_ptr;
+
+ if (available == 0) {
+ return 0; // buffer is empty
+ }
+
+ int n = 0;
+
+ if (available > 0) {
+ // read pointer is before write pointer, all available bytes can be read
+ n = available;
+ *is_part = false;
+
+ } else {
+ // read pointer is after write pointer, read bytes from read_ptr to end of the buffer
+ n = lb->size - lb->read_ptr;
+ *is_part = true;
+ }
+
+ *ptr = &(lb->data[lb->read_ptr]);
+ return n;
+}
+
+void logbuffer_mark_read(struct logbuffer_s *lb, int n)
+{
+ lb->read_ptr = (lb->read_ptr + n) % lb->size;
+}
diff --git a/src/modules/sdlog2/logbuffer.h b/src/modules/sdlog2/logbuffer.h
new file mode 100644
index 000000000..31521f722
--- /dev/null
+++ b/src/modules/sdlog2/logbuffer.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file logbuffer.h
+ *
+ * Ring FIFO buffer for binary log data.
+ *
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#ifndef SDLOG2_RINGBUFFER_H_
+#define SDLOG2_RINGBUFFER_H_
+
+#include <stdbool.h>
+
+struct logbuffer_s {
+ // pointers and size are in bytes
+ int write_ptr;
+ int read_ptr;
+ int size;
+ char *data;
+};
+
+int logbuffer_init(struct logbuffer_s *lb, int size);
+
+int logbuffer_count(struct logbuffer_s *lb);
+
+int logbuffer_is_empty(struct logbuffer_s *lb);
+
+bool logbuffer_write(struct logbuffer_s *lb, void *ptr, int size);
+
+int logbuffer_get_ptr(struct logbuffer_s *lb, void **ptr, bool *is_part);
+
+void logbuffer_mark_read(struct logbuffer_s *lb, int n);
+
+#endif
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
new file mode 100644
index 000000000..f53129688
--- /dev/null
+++ b/src/modules/sdlog2/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 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
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# sdlog2 Application
+#
+
+MODULE_COMMAND = sdlog2
+# The main thread only buffers to RAM, needs a high priority
+MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
+
+SRCS = sdlog2.c \
+ logbuffer.c
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
new file mode 100644
index 000000000..a14bd6f80
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2.c
@@ -0,0 +1,1178 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sdlog2.c
+ *
+ * Simple SD logger for flight data. Buffers new sensor values and
+ * does the heavy SD I/O in a low-priority worker thread.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <sys/prctl.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <poll.h>
+#include <stdlib.h>
+#include <string.h>
+#include <ctype.h>
+#include <systemlib/err.h>
+#include <unistd.h>
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_controls_effective.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/optical_flow.h>
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/rc_channels.h>
+
+#include <systemlib/systemlib.h>
+
+#include <mavlink/mavlink_log.h>
+
+#include "logbuffer.h"
+#include "sdlog2_format.h"
+#include "sdlog2_messages.h"
+
+#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
+ log_msgs_written++; \
+ } else { \
+ log_msgs_skipped++; \
+ /*printf("skip\n");*/ \
+ }
+
+#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \
+ fds[fdsc_count].fd = subs.##_var##_sub; \
+ fds[fdsc_count].events = POLLIN; \
+ fdsc_count++;
+
+
+//#define SDLOG2_DEBUG
+
+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 bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
+static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */
+static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
+static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
+static const int MAX_WRITE_CHUNK = 512;
+static const int MIN_BYTES_TO_WRITE = 512;
+
+static const char *mountpoint = "/fs/microsd";
+int log_file = -1;
+int mavlink_fd = -1;
+struct logbuffer_s lb;
+
+/* mutex / condition to synchronize threads */
+pthread_mutex_t logbuffer_mutex;
+pthread_cond_t logbuffer_cond;
+
+char folder_path[64];
+
+/* statistics counters */
+unsigned long log_bytes_written = 0;
+uint64_t start_time = 0;
+unsigned long log_msgs_written = 0;
+unsigned long log_msgs_skipped = 0;
+
+/* current state of logging */
+bool logging_enabled = false;
+/* enable logging on start (-e option) */
+bool log_on_start = false;
+/* enable logging when armed (-a option) */
+bool log_when_armed = false;
+/* delay = 1 / rate (rate defined by -r option) */
+useconds_t sleep_delay = 0;
+
+/* helper flag to track system state changes */
+bool flag_system_armed = false;
+
+pthread_t logwriter_pthread = 0;
+
+/**
+ * Log buffer writing thread. Open and close file here.
+ */
+static void *logwriter_thread(void *arg);
+
+/**
+ * SD log management function.
+ */
+__EXPORT int sdlog2_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of sd log deamon.
+ */
+int sdlog2_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void sdlog2_usage(const char *reason);
+
+/**
+ * Print the current status.
+ */
+static void sdlog2_status(void);
+
+/**
+ * Start logging: create new file and start log writer thread.
+ */
+void sdlog2_start_log();
+
+/**
+ * Stop logging: stop log writer thread and close log file.
+ */
+void sdlog2_stop_log();
+
+/**
+ * Write a header to log file: list of message formats.
+ */
+void write_formats(int fd);
+
+
+static bool file_exist(const char *filename);
+
+static int file_copy(const char *file_old, const char *file_new);
+
+static void handle_command(struct vehicle_command_s *cmd);
+
+static void handle_status(struct vehicle_status_s *cmd);
+
+/**
+ * Create folder for current logging session. Store folder name in 'log_folder'.
+ */
+static int create_logfolder();
+
+/**
+ * Select first free log file name and open it.
+ */
+static int open_logfile();
+
+static void
+sdlog2_usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a\n"
+ "\t-r\tLog rate in Hz, 0 means unlimited rate\n"
+ "\t-b\tLog buffer size in KiB, default is 8\n"
+ "\t-e\tEnable logging by default (if not, can be started by command)\n"
+ "\t-a\tLog only when armed (can be still overriden by command)\n");
+}
+
+/**
+ * The logger deamon 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_spawn().
+ */
+int sdlog2_main(int argc, char *argv[])
+{
+ if (argc < 2)
+ sdlog2_usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ printf("sdlog2 already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ deamon_task = task_spawn("sdlog2",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT - 30,
+ 2048,
+ sdlog2_thread_main,
+ (const char **)argv);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (!thread_running) {
+ printf("\tsdlog2 is not started\n");
+ }
+
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ sdlog2_status();
+
+ } else {
+ printf("\tsdlog2 not started\n");
+ }
+
+ exit(0);
+ }
+
+ sdlog2_usage("unrecognized command");
+ exit(1);
+}
+
+int create_logfolder()
+{
+ /* make folder on sdcard */
+ uint16_t folder_number = 1; // start with folder sess001
+ int mkdir_ret;
+
+ /* look for the next folder that does not exist */
+ while (folder_number <= MAX_NO_LOGFOLDER) {
+ /* set up folder path: e.g. /fs/microsd/sess001 */
+ sprintf(folder_path, "%s/sess%03u", mountpoint, folder_number);
+ mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO);
+ /* the result is -1 if the folder exists */
+
+ if (mkdir_ret == 0) {
+ /* folder does not exist, success */
+
+ /* copy parser script file */
+ // TODO
+ /*
+ char mfile_out[100];
+ sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber);
+ int ret = file_copy(mfile_in, mfile_out);
+
+ if (!ret) {
+ warnx("copied m file to %s", mfile_out);
+
+ } else {
+ warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out);
+ }
+ */
+
+ break;
+
+ } else if (mkdir_ret == -1) {
+ /* folder exists already */
+ folder_number++;
+ continue;
+
+ } else {
+ warn("failed creating new folder");
+ return -1;
+ }
+ }
+
+ if (folder_number >= MAX_NO_LOGFOLDER) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
+ warnx("all %d possible folders exist already.", MAX_NO_LOGFOLDER);
+ return -1;
+ }
+
+ return 0;
+}
+
+int open_logfile()
+{
+ /* make folder on sdcard */
+ uint16_t file_number = 1; // start with file log001
+
+ /* string to hold the path to the log */
+ char path_buf[64] = "";
+
+ int fd = 0;
+
+ /* look for the next file that does not exist */
+ while (file_number <= MAX_NO_LOGFILE) {
+ /* set up file path: e.g. /fs/microsd/sess001/log001.bin */
+ sprintf(path_buf, "%s/log%03u.bin", folder_path, file_number);
+
+ if (file_exist(path_buf)) {
+ file_number++;
+ continue;
+ }
+
+ fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC);
+
+ if (fd == 0) {
+ errx(1, "opening %s failed.", path_buf);
+ }
+
+ warnx("logging to: %s", path_buf);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf);
+
+ return fd;
+ }
+
+ if (file_number > MAX_NO_LOGFILE) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
+ warn("all %d possible files exist already", MAX_NO_LOGFILE);
+ return -1;
+ }
+
+ return 0;
+}
+
+static void *logwriter_thread(void *arg)
+{
+ /* set name */
+ prctl(PR_SET_NAME, "sdlog2_writer", 0);
+
+ struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
+
+ int log_file = open_logfile();
+
+ /* write log messages formats */
+ write_formats(log_file);
+
+ int poll_count = 0;
+
+ void *read_ptr;
+ int n = 0;
+ bool should_wait = false;
+ bool is_part = false;
+
+ while (!thread_should_exit && !logwriter_should_exit) {
+
+ /* make sure threads are synchronized */
+ pthread_mutex_lock(&logbuffer_mutex);
+
+ /* update read pointer if needed */
+ if (n > 0) {
+ logbuffer_mark_read(&lb, n);
+ }
+
+ /* only wait if no data is available to process */
+ if (should_wait) {
+ /* blocking wait for new data at this line */
+ pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex);
+ }
+
+ /* only get pointer to thread-safe data, do heavy I/O a few lines down */
+ int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part);
+
+ /* continue */
+ pthread_mutex_unlock(&logbuffer_mutex);
+
+ if (available > 0) {
+ /* do heavy IO here */
+ if (available > MAX_WRITE_CHUNK) {
+ n = MAX_WRITE_CHUNK;
+
+ } else {
+ n = available;
+ }
+
+ n = write(log_file, read_ptr, n);
+
+ should_wait = (n == available) && !is_part;
+#ifdef SDLOG2_DEBUG
+ printf("%i wrote: %i of %i, is_part=%i, should_wait=%i", poll_count, n, available, (int)is_part, (int)should_wait);
+#endif
+
+ if (n < 0) {
+ thread_should_exit = true;
+ err(1, "error writing log file");
+ }
+
+ if (n > 0) {
+ log_bytes_written += n;
+ }
+
+ } else {
+ should_wait = true;
+ }
+
+ if (poll_count % 10 == 0) {
+ fsync(log_file);
+ }
+
+ poll_count++;
+ }
+
+ fsync(log_file);
+ close(log_file);
+
+ return OK;
+}
+
+void sdlog2_start_log()
+{
+ warnx("start logging.");
+ mavlink_log_info(mavlink_fd, "[sdlog2] start logging");
+
+ /* initialize statistics counter */
+ log_bytes_written = 0;
+ start_time = hrt_absolute_time();
+ log_msgs_written = 0;
+ log_msgs_skipped = 0;
+
+ /* initialize log buffer emptying thread */
+ pthread_attr_t receiveloop_attr;
+ pthread_attr_init(&receiveloop_attr);
+
+ struct sched_param param;
+ /* low priority, as this is expensive disk I/O */
+ param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
+ (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+
+ pthread_attr_setstacksize(&receiveloop_attr, 2048);
+
+ logwriter_should_exit = false;
+ pthread_t thread;
+
+ /* start log buffer emptying thread */
+ if (0 != pthread_create(&thread, &receiveloop_attr, logwriter_thread, &lb)) {
+ errx(1, "error creating logwriter thread");
+ }
+
+ logging_enabled = true;
+ // XXX we have to destroy the attr at some point
+}
+
+void sdlog2_stop_log()
+{
+ warnx("stop logging.");
+ mavlink_log_info(mavlink_fd, "[sdlog2] stop logging");
+
+ logging_enabled = false;
+ logwriter_should_exit = true;
+
+ /* wake up write thread one last time */
+ pthread_mutex_lock(&logbuffer_mutex);
+ pthread_cond_signal(&logbuffer_cond);
+ /* unlock, now the writer thread may return */
+ pthread_mutex_unlock(&logbuffer_mutex);
+
+ /* wait for write thread to return */
+ (void)pthread_join(logwriter_pthread, NULL);
+
+ sdlog2_status();
+}
+
+
+void write_formats(int fd)
+{
+ /* construct message format packet */
+ struct {
+ LOG_PACKET_HEADER;
+ struct log_format_s body;
+ } log_format_packet = {
+ LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG),
+ };
+
+ /* fill message format packet for each format and write to log */
+ int i;
+
+ for (i = 0; i < log_formats_num; i++) {
+ log_format_packet.body = log_formats[i];
+ write(fd, &log_format_packet, sizeof(log_format_packet));
+ }
+
+ fsync(fd);
+}
+
+int sdlog2_thread_main(int argc, char *argv[])
+{
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ if (mavlink_fd < 0) {
+ warnx("failed to open MAVLink log stream, start mavlink app first.");
+ }
+
+ /* log buffer size */
+ int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
+
+ /* work around some stupidity in task_create's argv handling */
+ argc -= 2;
+ argv += 2;
+ int ch;
+
+ while ((ch = getopt(argc, argv, "r:b:ea")) != EOF) {
+ switch (ch) {
+ case 'r': {
+ unsigned long r = strtoul(optarg, NULL, 10);
+
+ if (r == 0) {
+ sleep_delay = 0;
+
+ } else {
+ sleep_delay = 1000000 / r;
+ }
+ }
+ break;
+
+ case 'b': {
+ unsigned long s = strtoul(optarg, NULL, 10);
+
+ if (s < 1) {
+ s = 1;
+ }
+
+ log_buffer_size = 1024 * s;
+ }
+ break;
+
+ case 'e':
+ log_on_start = true;
+ break;
+
+ case 'a':
+ log_when_armed = true;
+ break;
+
+ case '?':
+ if (optopt == 'c') {
+ warnx("Option -%c requires an argument.", optopt);
+
+ } else if (isprint(optopt)) {
+ warnx("Unknown option `-%c'.", optopt);
+
+ } else {
+ warnx("Unknown option character `\\x%x'.", optopt);
+ }
+
+ default:
+ sdlog2_usage("unrecognized flag");
+ errx(1, "exiting.");
+ }
+ }
+
+ if (!file_exist(mountpoint)) {
+ errx(1, "logging mount point %s not present, exiting.", mountpoint);
+ }
+
+ if (create_logfolder()) {
+ errx(1, "unable to create logging folder, exiting.");
+ }
+
+ /* only print logging path, important to find log file later */
+ warnx("logging to directory: %s", folder_path);
+
+ /* initialize log buffer with specified size */
+ warnx("log buffer size: %i bytes.", log_buffer_size);
+
+ if (OK != logbuffer_init(&lb, log_buffer_size)) {
+ errx(1, "can't allocate log buffer, exiting.");
+ }
+
+ /* file descriptors to wait for */
+ struct pollfd fds_control[2];
+
+ /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
+ /* number of messages */
+ const ssize_t fdsc = 15;
+ /* Sanity check variable and index */
+ ssize_t fdsc_count = 0;
+ /* file descriptors to wait for */
+ struct pollfd fds[fdsc];
+
+ struct vehicle_status_s buf_status;
+ memset(&buf_status, 0, sizeof(buf_status));
+
+ /* warning! using union here to save memory, elements should be used separately! */
+ union {
+ struct vehicle_command_s cmd;
+ struct sensor_combined_s sensor;
+ struct vehicle_attitude_s att;
+ struct vehicle_attitude_setpoint_s att_sp;
+ struct actuator_outputs_s act_outputs;
+ struct actuator_controls_s act_controls;
+ struct actuator_controls_effective_s act_controls_effective;
+ struct vehicle_local_position_s local_pos;
+ struct vehicle_local_position_setpoint_s local_pos_sp;
+ struct vehicle_global_position_s global_pos;
+ struct vehicle_gps_position_s gps_pos;
+ struct vehicle_vicon_position_s vicon_pos;
+ struct optical_flow_s flow;
+ struct rc_channels_s rc;
+ struct differential_pressure_s diff_pres;
+ struct airspeed_s airspeed;
+ } buf;
+ memset(&buf, 0, sizeof(buf));
+
+ struct {
+ int cmd_sub;
+ int status_sub;
+ int sensor_sub;
+ int att_sub;
+ int att_sp_sub;
+ int act_outputs_sub;
+ int act_controls_sub;
+ int act_controls_effective_sub;
+ int local_pos_sub;
+ int local_pos_sp_sub;
+ int global_pos_sub;
+ int gps_pos_sub;
+ int vicon_pos_sub;
+ int flow_sub;
+ int rc_sub;
+ } subs;
+
+ /* log message buffer: header + body */
+#pragma pack(push, 1)
+ struct {
+ LOG_PACKET_HEADER;
+ union {
+ struct log_TIME_s log_TIME;
+ struct log_ATT_s log_ATT;
+ struct log_ATSP_s log_ATSP;
+ struct log_IMU_s log_IMU;
+ struct log_SENS_s log_SENS;
+ struct log_LPOS_s log_LPOS;
+ struct log_LPSP_s log_LPSP;
+ struct log_GPS_s log_GPS;
+ struct log_ATTC_s log_ATTC;
+ struct log_STAT_s log_STAT;
+ struct log_RC_s log_RC;
+ struct log_OUT0_s log_OUT0;
+ } body;
+ } log_msg = {
+ LOG_PACKET_HEADER_INIT(0)
+ };
+#pragma pack(pop)
+ memset(&log_msg.body, 0, sizeof(log_msg.body));
+
+ /* --- VEHICLE COMMAND --- */
+ subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ fds[fdsc_count].fd = subs.cmd_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- VEHICLE STATUS --- */
+ subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ fds[fdsc_count].fd = subs.status_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GPS POSITION --- */
+ subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ fds[fdsc_count].fd = subs.gps_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- SENSORS COMBINED --- */
+ subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ fds[fdsc_count].fd = subs.sensor_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ATTITUDE --- */
+ subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ fds[fdsc_count].fd = subs.att_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ATTITUDE SETPOINT --- */
+ subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ fds[fdsc_count].fd = subs.att_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ACTUATOR OUTPUTS --- */
+ subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
+ fds[fdsc_count].fd = subs.act_outputs_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ACTUATOR CONTROL --- */
+ subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
+ fds[fdsc_count].fd = subs.act_controls_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- ACTUATOR CONTROL EFFECTIVE --- */
+ subs.act_controls_effective_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE);
+ fds[fdsc_count].fd = subs.act_controls_effective_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- LOCAL POSITION --- */
+ subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
+ fds[fdsc_count].fd = subs.local_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- LOCAL POSITION SETPOINT --- */
+ subs.local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ fds[fdsc_count].fd = subs.local_pos_sp_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- GLOBAL POSITION --- */
+ subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ fds[fdsc_count].fd = subs.global_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- VICON POSITION --- */
+ subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
+ fds[fdsc_count].fd = subs.vicon_pos_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- OPTICAL FLOW --- */
+ subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
+ fds[fdsc_count].fd = subs.flow_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* --- RC CHANNELS --- */
+ subs.rc_sub = orb_subscribe(ORB_ID(rc_channels));
+ fds[fdsc_count].fd = subs.rc_sub;
+ fds[fdsc_count].events = POLLIN;
+ fdsc_count++;
+
+ /* WARNING: If you get the error message below,
+ * then the number of registered messages (fdsc)
+ * differs from the number of messages in the above list.
+ */
+ if (fdsc_count > fdsc) {
+ warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.", __FILE__, __LINE__);
+ fdsc_count = fdsc;
+ }
+
+ /*
+ * set up poll to block for new data,
+ * wait for a maximum of 1000 ms
+ */
+ const int poll_timeout = 1000;
+
+ thread_running = true;
+
+ /* initialize thread synchronization */
+ pthread_mutex_init(&logbuffer_mutex, NULL);
+ pthread_cond_init(&logbuffer_cond, NULL);
+
+ /* track changes in sensor_combined topic */
+ uint16_t gyro_counter = 0;
+ uint16_t accelerometer_counter = 0;
+ uint16_t magnetometer_counter = 0;
+ uint16_t baro_counter = 0;
+ uint16_t differential_pressure_counter = 0;
+
+ /* enable logging on start if needed */
+ if (log_on_start)
+ sdlog2_start_log();
+
+ while (!thread_should_exit) {
+ /* decide use usleep() or blocking poll() */
+ bool use_sleep = sleep_delay > 0 && logging_enabled;
+
+ /* poll all topics if logging enabled or only management (first 2) if not */
+ int poll_ret = poll(fds, logging_enabled ? fdsc_count : 2, use_sleep ? 0 : poll_timeout);
+
+ /* handle the poll result */
+ if (poll_ret < 0) {
+ warnx("ERROR: poll error, stop logging.");
+ thread_should_exit = true;
+
+ } else if (poll_ret > 0) {
+
+ /* check all data subscriptions only if logging enabled,
+ * logging_enabled can be changed while checking vehicle_command and vehicle_status */
+ bool check_data = logging_enabled;
+ int ifds = 0;
+ int handled_topics = 0;
+
+ /* --- VEHICLE COMMAND - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd);
+ handle_command(&buf.cmd);
+ handled_topics++;
+ }
+
+ /* --- VEHICLE STATUS - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_status), subs.status_sub, &buf_status);
+
+ if (log_when_armed) {
+ handle_status(&buf_status);
+ }
+
+ handled_topics++;
+ }
+
+ if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
+ continue;
+ }
+
+ ifds = 1; // Begin from fds[1] again
+
+ pthread_mutex_lock(&logbuffer_mutex);
+
+ /* write time stamp message */
+ log_msg.msg_type = LOG_TIME_MSG;
+ log_msg.body.log_TIME.t = hrt_absolute_time();
+ LOGBUFFER_WRITE_AND_COUNT(TIME);
+
+ /* --- VEHICLE STATUS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ // Don't orb_copy, it's already done few lines above
+ log_msg.msg_type = LOG_STAT_MSG;
+ log_msg.body.log_STAT.state = (unsigned char) buf_status.state_machine;
+ log_msg.body.log_STAT.flight_mode = (unsigned char) buf_status.flight_mode;
+ log_msg.body.log_STAT.manual_control_mode = (unsigned char) buf_status.manual_control_mode;
+ log_msg.body.log_STAT.manual_sas_mode = (unsigned char) buf_status.manual_sas_mode;
+ log_msg.body.log_STAT.armed = (unsigned char) buf_status.flag_system_armed;
+ log_msg.body.log_STAT.battery_voltage = buf_status.voltage_battery;
+ log_msg.body.log_STAT.battery_current = buf_status.current_battery;
+ log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
+ log_msg.body.log_STAT.battery_warning = (unsigned char) buf_status.battery_warning;
+ LOGBUFFER_WRITE_AND_COUNT(STAT);
+ }
+
+ /* --- GPS POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
+ log_msg.msg_type = LOG_GPS_MSG;
+ log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec;
+ log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type;
+ log_msg.body.log_GPS.eph = buf.gps_pos.eph_m;
+ log_msg.body.log_GPS.epv = buf.gps_pos.epv_m;
+ log_msg.body.log_GPS.lat = buf.gps_pos.lat;
+ log_msg.body.log_GPS.lon = buf.gps_pos.lon;
+ log_msg.body.log_GPS.alt = buf.gps_pos.alt * 0.001;
+ log_msg.body.log_GPS.vel_n = buf.gps_pos.vel_n_m_s;
+ log_msg.body.log_GPS.vel_e = buf.gps_pos.vel_e_m_s;
+ log_msg.body.log_GPS.vel_d = buf.gps_pos.vel_d_m_s;
+ log_msg.body.log_GPS.cog = buf.gps_pos.cog_rad;
+ LOGBUFFER_WRITE_AND_COUNT(GPS);
+ }
+
+ /* --- SENSOR COMBINED --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor);
+ bool write_IMU = false;
+ bool write_SENS = false;
+
+ if (buf.sensor.gyro_counter != gyro_counter) {
+ gyro_counter = buf.sensor.gyro_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.accelerometer_counter != accelerometer_counter) {
+ accelerometer_counter = buf.sensor.accelerometer_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.magnetometer_counter != magnetometer_counter) {
+ magnetometer_counter = buf.sensor.magnetometer_counter;
+ write_IMU = true;
+ }
+
+ if (buf.sensor.baro_counter != baro_counter) {
+ baro_counter = buf.sensor.baro_counter;
+ write_SENS = true;
+ }
+
+ if (buf.sensor.differential_pressure_counter != differential_pressure_counter) {
+ differential_pressure_counter = buf.sensor.differential_pressure_counter;
+ write_SENS = true;
+ }
+
+ if (write_IMU) {
+ log_msg.msg_type = LOG_IMU_MSG;
+ log_msg.body.log_IMU.gyro_x = buf.sensor.gyro_rad_s[0];
+ log_msg.body.log_IMU.gyro_y = buf.sensor.gyro_rad_s[1];
+ log_msg.body.log_IMU.gyro_z = buf.sensor.gyro_rad_s[2];
+ log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer_m_s2[0];
+ log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer_m_s2[1];
+ log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer_m_s2[2];
+ log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer_ga[0];
+ log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer_ga[1];
+ log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer_ga[2];
+ LOGBUFFER_WRITE_AND_COUNT(IMU);
+ }
+
+ if (write_SENS) {
+ log_msg.msg_type = LOG_SENS_MSG;
+ log_msg.body.log_SENS.baro_pres = buf.sensor.baro_pres_mbar;
+ log_msg.body.log_SENS.baro_alt = buf.sensor.baro_alt_meter;
+ log_msg.body.log_SENS.baro_temp = buf.sensor.baro_temp_celcius;
+ log_msg.body.log_SENS.diff_pres = buf.sensor.differential_pressure_pa;
+ LOGBUFFER_WRITE_AND_COUNT(SENS);
+ }
+ }
+
+ /* --- ATTITUDE --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att);
+ log_msg.msg_type = LOG_ATT_MSG;
+ log_msg.body.log_ATT.roll = buf.att.roll;
+ log_msg.body.log_ATT.pitch = buf.att.pitch;
+ log_msg.body.log_ATT.yaw = buf.att.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(ATT);
+ }
+
+ /* --- ATTITUDE SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.att_sp_sub, &buf.att_sp);
+ log_msg.msg_type = LOG_ATSP_MSG;
+ log_msg.body.log_ATSP.roll_sp = buf.att_sp.roll_body;
+ log_msg.body.log_ATSP.pitch_sp = buf.att_sp.pitch_body;
+ log_msg.body.log_ATSP.yaw_sp = buf.att_sp.yaw_body;
+ LOGBUFFER_WRITE_AND_COUNT(ATSP);
+ }
+
+ /* --- ACTUATOR OUTPUTS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs);
+ log_msg.msg_type = LOG_OUT0_MSG;
+ memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output));
+ LOGBUFFER_WRITE_AND_COUNT(OUT0);
+ }
+
+ /* --- ACTUATOR CONTROL --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.act_controls_sub, &buf.act_controls);
+ log_msg.msg_type = LOG_ATTC_MSG;
+ log_msg.body.log_ATTC.roll = buf.act_controls.control[0];
+ log_msg.body.log_ATTC.pitch = buf.act_controls.control[1];
+ log_msg.body.log_ATTC.yaw = buf.act_controls.control[2];
+ log_msg.body.log_ATTC.thrust = buf.act_controls.control[3];
+ LOGBUFFER_WRITE_AND_COUNT(ATTC);
+ }
+
+ /* --- ACTUATOR CONTROL EFFECTIVE --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, subs.act_controls_effective_sub, &buf.act_controls_effective);
+ // TODO not implemented yet
+ }
+
+ /* --- LOCAL POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos);
+ log_msg.msg_type = LOG_LPOS_MSG;
+ log_msg.body.log_LPOS.x = buf.local_pos.x;
+ log_msg.body.log_LPOS.y = buf.local_pos.y;
+ log_msg.body.log_LPOS.z = buf.local_pos.z;
+ log_msg.body.log_LPOS.vx = buf.local_pos.vx;
+ log_msg.body.log_LPOS.vy = buf.local_pos.vy;
+ log_msg.body.log_LPOS.vz = buf.local_pos.vz;
+ log_msg.body.log_LPOS.hdg = buf.local_pos.hdg;
+ log_msg.body.log_LPOS.home_lat = buf.local_pos.home_lat;
+ log_msg.body.log_LPOS.home_lon = buf.local_pos.home_lon;
+ log_msg.body.log_LPOS.home_alt = buf.local_pos.home_alt;
+ LOGBUFFER_WRITE_AND_COUNT(LPOS);
+ }
+
+ /* --- LOCAL POSITION SETPOINT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_local_position_setpoint), subs.local_pos_sp_sub, &buf.local_pos_sp);
+ log_msg.msg_type = LOG_LPSP_MSG;
+ log_msg.body.log_LPSP.x = buf.local_pos_sp.x;
+ log_msg.body.log_LPSP.y = buf.local_pos_sp.y;
+ log_msg.body.log_LPSP.z = buf.local_pos_sp.z;
+ log_msg.body.log_LPSP.yaw = buf.local_pos_sp.yaw;
+ LOGBUFFER_WRITE_AND_COUNT(LPSP);
+ }
+
+ /* --- GLOBAL POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos);
+ // TODO not implemented yet
+ }
+
+ /* --- VICON POSITION --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos);
+ // TODO not implemented yet
+ }
+
+ /* --- FLOW --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow);
+ // TODO not implemented yet
+ }
+
+ /* --- RC CHANNELS --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(rc_channels), subs.rc_sub, &buf.rc);
+ log_msg.msg_type = LOG_RC_MSG;
+ /* Copy only the first 8 channels of 14 */
+ memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
+ LOGBUFFER_WRITE_AND_COUNT(RC);
+ }
+
+ /* signal the other thread new data, but not yet unlock */
+ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
+#ifdef SDLOG2_DEBUG
+ printf("signal %i", logbuffer_count(&lb));
+#endif
+ /* only request write if several packets can be written at once */
+ pthread_cond_signal(&logbuffer_cond);
+ }
+
+ /* unlock, now the writer thread may run */
+ pthread_mutex_unlock(&logbuffer_mutex);
+ }
+
+ if (use_sleep) {
+ usleep(sleep_delay);
+ }
+ }
+
+ if (logging_enabled)
+ sdlog2_stop_log();
+
+ pthread_mutex_destroy(&logbuffer_mutex);
+ pthread_cond_destroy(&logbuffer_cond);
+
+ warnx("exiting.");
+
+ thread_running = false;
+
+ return 0;
+}
+
+void sdlog2_status()
+{
+ float kibibytes = log_bytes_written / 1024.0f;
+ float mebibytes = kibibytes / 1024.0f;
+ float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
+
+ warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs.", log_msgs_written, log_msgs_skipped);
+}
+
+/**
+ * @return 0 if file exists
+ */
+bool file_exist(const char *filename)
+{
+ struct stat buffer;
+ return stat(filename, &buffer) == 0;
+}
+
+int file_copy(const char *file_old, const char *file_new)
+{
+ FILE *source, *target;
+ source = fopen(file_old, "r");
+ int ret = 0;
+
+ if (source == NULL) {
+ warnx("failed opening input file to copy.");
+ return 1;
+ }
+
+ target = fopen(file_new, "w");
+
+ if (target == NULL) {
+ fclose(source);
+ warnx("failed to open output file to copy.");
+ return 1;
+ }
+
+ char buf[128];
+ int nread;
+
+ while ((nread = fread(buf, 1, sizeof(buf), source)) > 0) {
+ ret = fwrite(buf, 1, nread, target);
+
+ if (ret <= 0) {
+ warnx("error writing file.");
+ ret = 1;
+ break;
+ }
+ }
+
+ fsync(fileno(target));
+
+ fclose(source);
+ fclose(target);
+
+ return ret;
+}
+
+void handle_command(struct vehicle_command_s *cmd)
+{
+ /* result of the command */
+ uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
+ int param;
+
+ /* request to set different system mode */
+ switch (cmd->command) {
+
+ case VEHICLE_CMD_PREFLIGHT_STORAGE:
+ param = (int)(cmd->param3);
+
+ if (param == 1) {
+ sdlog2_start_log();
+
+ } else if (param == 0) {
+ sdlog2_stop_log();
+ }
+
+ break;
+
+ default:
+ /* silently ignore */
+ break;
+ }
+}
+
+void handle_status(struct vehicle_status_s *status)
+{
+ if (status->flag_system_armed != flag_system_armed) {
+ flag_system_armed = status->flag_system_armed;
+
+ if (flag_system_armed) {
+ sdlog2_start_log();
+
+ } else {
+ sdlog2_stop_log();
+ }
+ }
+}
diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h
new file mode 100644
index 000000000..59b91d90d
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2_format.h
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sdlog2_format.h
+ *
+ * General log format structures and macro.
+ *
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ */
+
+/*
+Format characters in the format string for binary log messages
+ b : int8_t
+ B : uint8_t
+ h : int16_t
+ H : uint16_t
+ i : int32_t
+ I : uint32_t
+ f : float
+ n : char[4]
+ N : char[16]
+ Z : char[64]
+ c : int16_t * 100
+ C : uint16_t * 100
+ e : int32_t * 100
+ E : uint32_t * 100
+ L : int32_t latitude/longitude
+ M : uint8_t flight mode
+
+ q : int64_t
+ Q : uint64_t
+ */
+
+#ifndef SDLOG2_FORMAT_H_
+#define SDLOG2_FORMAT_H_
+
+#define LOG_PACKET_HEADER_LEN 3
+#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type;
+#define LOG_PACKET_HEADER_INIT(id) .head1 = HEAD_BYTE1, .head2 = HEAD_BYTE2, .msg_type = id
+
+// once the logging code is all converted we will remove these from
+// this header
+#define HEAD_BYTE1 0xA3 // Decimal 163
+#define HEAD_BYTE2 0x95 // Decimal 149
+
+struct log_format_s {
+ uint8_t type;
+ uint8_t length; // full packet length including header
+ char name[4];
+ char format[16];
+ char labels[64];
+};
+
+#define LOG_FORMAT(_name, _format, _labels) { \
+ .type = LOG_##_name##_MSG, \
+ .length = sizeof(struct log_##_name##_s) + LOG_PACKET_HEADER_LEN, \
+ .name = #_name, \
+ .format = _format, \
+ .labels = _labels \
+ }
+
+#define LOG_FORMAT_MSG 0x80
+
+#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s)
+
+#endif /* SDLOG2_FORMAT_H_ */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
new file mode 100644
index 000000000..40763ee1e
--- /dev/null
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -0,0 +1,191 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sdlog2_messages.h
+ *
+ * Log messages and structures definition.
+ *
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#ifndef SDLOG2_MESSAGES_H_
+#define SDLOG2_MESSAGES_H_
+
+#include "sdlog2_format.h"
+
+/* define message formats */
+
+#pragma pack(push, 1)
+/* --- TIME - TIME STAMP --- */
+#define LOG_TIME_MSG 1
+struct log_TIME_s {
+ uint64_t t;
+};
+
+/* --- ATT - ATTITUDE --- */
+#define LOG_ATT_MSG 2
+struct log_ATT_s {
+ float roll;
+ float pitch;
+ float yaw;
+};
+
+/* --- ATSP - ATTITUDE SET POINT --- */
+#define LOG_ATSP_MSG 3
+struct log_ATSP_s {
+ float roll_sp;
+ float pitch_sp;
+ float yaw_sp;
+};
+
+/* --- IMU - IMU SENSORS --- */
+#define LOG_IMU_MSG 4
+struct log_IMU_s {
+ float acc_x;
+ float acc_y;
+ float acc_z;
+ float gyro_x;
+ float gyro_y;
+ float gyro_z;
+ float mag_x;
+ float mag_y;
+ float mag_z;
+};
+
+/* --- SENS - OTHER SENSORS --- */
+#define LOG_SENS_MSG 5
+struct log_SENS_s {
+ float baro_pres;
+ float baro_alt;
+ float baro_temp;
+ float diff_pres;
+};
+
+/* --- LPOS - LOCAL POSITION --- */
+#define LOG_LPOS_MSG 6
+struct log_LPOS_s {
+ float x;
+ float y;
+ float z;
+ float vx;
+ float vy;
+ float vz;
+ float hdg;
+ int32_t home_lat;
+ int32_t home_lon;
+ float home_alt;
+};
+
+/* --- LPSP - LOCAL POSITION SETPOINT --- */
+#define LOG_LPSP_MSG 7
+struct log_LPSP_s {
+ float x;
+ float y;
+ float z;
+ float yaw;
+};
+
+/* --- GPS - GPS POSITION --- */
+#define LOG_GPS_MSG 8
+struct log_GPS_s {
+ uint64_t gps_time;
+ uint8_t fix_type;
+ float eph;
+ float epv;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+ float vel_n;
+ float vel_e;
+ float vel_d;
+ float cog;
+};
+
+/* --- ATTC - ATTITUDE CONTROLS (ACTUATOR_0 CONTROLS)--- */
+#define LOG_ATTC_MSG 9
+struct log_ATTC_s {
+ float roll;
+ float pitch;
+ float yaw;
+ float thrust;
+};
+
+/* --- STAT - VEHICLE STATE --- */
+#define LOG_STAT_MSG 10
+struct log_STAT_s {
+ unsigned char state;
+ unsigned char flight_mode;
+ unsigned char manual_control_mode;
+ unsigned char manual_sas_mode;
+ unsigned char armed;
+ float battery_voltage;
+ float battery_current;
+ float battery_remaining;
+ unsigned char battery_warning;
+};
+
+/* --- RC - RC INPUT CHANNELS --- */
+#define LOG_RC_MSG 11
+struct log_RC_s {
+ float channel[8];
+};
+
+/* --- OUT0 - ACTUATOR_0 OUTPUT --- */
+#define LOG_OUT0_MSG 12
+struct log_OUT0_s {
+ float output[8];
+};
+#pragma pack(pop)
+
+/* construct list of all message formats */
+
+static const struct log_format_s log_formats[] = {
+ LOG_FORMAT(TIME, "Q", "StartTime"),
+ LOG_FORMAT(ATT, "fff", "Roll,Pitch,Yaw"),
+ LOG_FORMAT(ATSP, "fff", "RollSP,PitchSP,YawSP"),
+ LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
+ LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,Heading,HomeLat,HomeLon,HomeAlt"),
+ LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
+ LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
+ LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
+ LOG_FORMAT(STAT, "BBBBBfffB", "State,FlightMode,CtlMode,SASMode,Armed,BatV,BatC,BatRem,BatWarn"),
+ LOG_FORMAT(RC, "ffffffff", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7"),
+ LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
+};
+
+static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);
+
+#endif /* SDLOG2_MESSAGES_H_ */
diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c
index 6746e8ff3..6463e6489 100644
--- a/src/modules/systemlib/geo/geo.c
+++ b/src/modules/systemlib/geo/geo.c
@@ -185,12 +185,11 @@ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, dou
double d_lat = lat_next_rad - lat_now_rad;
double d_lon = lon_next_rad - lon_now_rad;
- double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
+ double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0d) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a));
const double radius_earth = 6371000.0d;
-
- return radius_earth * c;
+ return radius_earth * c;
}
__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
diff --git a/src/modules/systemlib/geo/geo.h b/src/modules/systemlib/geo/geo.h
index 0c0b5c533..84097b49f 100644
--- a/src/modules/systemlib/geo/geo.h
+++ b/src/modules/systemlib/geo/geo.h
@@ -82,8 +82,24 @@ __EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
*/
__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
+/**
+ * Returns the distance to the next waypoint in meters.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+/**
+ * Returns the bearing to the next waypoint in radians.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);