aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorHyon Lim (Retina) <limhyon@gmail.com>2013-05-21 16:11:03 +1000
committerHyon Lim (Retina) <limhyon@gmail.com>2013-05-23 16:20:38 +1000
commit1caddb7bbb53f3017e2ee67742531b2159999658 (patch)
treeda8cc4b202cb6bd8e8ad7295fbf408a3ab0edd5a /src
parent2135628254fa9035c3cbb7db8ed9c05bb3dd172a (diff)
downloadpx4-firmware-1caddb7bbb53f3017e2ee67742531b2159999658.tar.gz
px4-firmware-1caddb7bbb53f3017e2ee67742531b2159999658.tar.bz2
px4-firmware-1caddb7bbb53f3017e2ee67742531b2159999658.zip
Initial work of so3 nonlinear complementary filter
Diffstat (limited to 'src')
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp610
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c44
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h32
-rw-r--r--src/modules/attitude_estimator_so3_comp/module.mk8
4 files changed, 694 insertions, 0 deletions
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..381b0df75
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
@@ -0,0 +1,610 @@
+/*
+ * @file attitude_estimator_so3_comp_main.c
+ *
+ * Nonlinear SO3 filter for Attitude Estimation.
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdlib.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 */
+volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to auxiliary frame
+
+/**
+ * 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} [-p <additional params>]\n\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,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ 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 x) {
+ float halfx = 0.5f * x;
+ float y = x;
+ long i = *(long*)&y;
+ i = 0x5f3759df - (i>>1);
+ y = *(float*)&i;
+ y = y * (1.5f - (halfx * y * y));
+ return y;
+}
+
+void MahonyAHRSupdateIMU(float gx, float gy, float gz, float ax, float ay, float az, float twoKp, float twoKi, float dt) {
+ float recipNorm;
+ float halfvx, halfvy, halfvz;
+ float halfex, halfey, halfez;
+ float qa, qb, qc;
+
+ // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+ if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
+
+ // Normalise accelerometer measurement
+ recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+ ax *= recipNorm;
+ ay *= recipNorm;
+ az *= recipNorm;
+
+ // Estimated direction of gravity and vector perpendicular to magnetic flux
+ halfvx = q1 * q3 - q0 * q2;
+ halfvy = q0 * q1 + q2 * q3;
+ halfvz = q0 * q0 - 0.5f + q3 * q3;
+
+ // Error is sum of cross product between estimated and measured direction of gravity
+ halfex = (ay * halfvz - az * halfvy);
+ halfey = (az * halfvx - ax * halfvz);
+ halfez = (ax * halfvy - ay * halfvx);
+
+ // Compute and apply integral feedback if enabled
+ if(twoKi > 0.0f) {
+ integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
+ integralFBy += twoKi * halfey * dt;
+ integralFBz += twoKi * halfez * dt;
+ gx += integralFBx; // apply integral feedback
+ gy += integralFBy;
+ gz += integralFBz;
+ }
+ else {
+ integralFBx = 0.0f; // prevent integral windup
+ integralFBy = 0.0f;
+ integralFBz = 0.0f;
+ }
+
+ // Apply proportional feedback
+ gx += twoKp * halfex;
+ gy += twoKp * halfey;
+ gz += twoKp * halfez;
+ }
+
+ // Integrate rate of change of quaternion
+ gx *= (0.5f * dt); // pre-multiply common factors
+ gy *= (0.5f * dt);
+ gz *= (0.5f * dt);
+ qa = q0;
+ qb = q1;
+ qc = q2;
+ q0 += (-qb * gx - qc * gy - q3 * gz);
+ q1 += (qa * gx + qc * gz - q3 * gy);
+ q2 += (qa * gy - qb * gz + q3 * gx);
+ q3 += (qa * gz + qb * gy - qc * gx);
+
+ // Normalise quaternion
+ recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+ q0 *= recipNorm;
+ q1 *= recipNorm;
+ q2 *= recipNorm;
+ q3 *= recipNorm;
+}
+
+void MahonyAHRSupdate(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 q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;
+ float hx, hy, bx, bz;
+ float halfvx, halfvy, halfvz, halfwx, halfwy, halfwz;
+ float halfex, halfey, halfez;
+ float qa, qb, qc;
+
+ // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer normalisation)
+ if((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
+ MahonyAHRSupdateIMU(gx, gy, gz, ax, ay, az, twoKp, twoKi, dt);
+ return;
+ }
+
+ // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+ if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
+
+ // Normalise accelerometer measurement
+ recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+ ax *= recipNorm;
+ ay *= recipNorm;
+ az *= recipNorm;
+
+ // Normalise magnetometer measurement
+ recipNorm = invSqrt(mx * mx + my * my + mz * mz);
+ mx *= recipNorm;
+ my *= recipNorm;
+ mz *= 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;
+
+ // 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));
+ bx = sqrt(hx * hx + hy * hy);
+ bz = 2.0f * (mx * (q1q3 - q0q2) + my * (q2q3 + q0q1) + mz * (0.5f - q1q1 - q2q2));
+
+ // Estimated direction of gravity and magnetic field
+ halfvx = q1q3 - q0q2;
+ halfvy = q0q1 + q2q3;
+ halfvz = q0q0 - 0.5f + q3q3;
+ 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 = (ay * halfvz - az * halfvy) + (my * halfwz - mz * halfwy);
+ halfey = (az * halfvx - ax * halfvz) + (mz * halfwx - mx * halfwz);
+ halfez = (ax * halfvy - ay * halfvx) + (mx * halfwy - my * halfwx);
+
+ // Compute and apply integral feedback if enabled
+ if(twoKi > 0.0f) {
+ integralFBx += twoKi * halfex * dt; // integral error scaled by Ki
+ integralFBy += twoKi * halfey * dt;
+ integralFBz += twoKi * halfez * dt;
+ gx += integralFBx; // apply integral feedback
+ gy += integralFBy;
+ gz += integralFBz;
+ }
+ else {
+ integralFBx = 0.0f; // prevent integral windup
+ integralFBy = 0.0f;
+ integralFBz = 0.0f;
+ }
+
+ // Apply proportional feedback
+ gx += twoKp * halfex;
+ gy += twoKp * halfey;
+ gz += twoKp * halfez;
+ }
+
+ // Integrate rate of change of quaternion
+ gx *= (0.5f * dt); // pre-multiply common factors
+ gy *= (0.5f * dt);
+ gz *= (0.5f * dt);
+ qa = q0;
+ qb = q1;
+ qc = q2;
+ q0 += (-qb * gx - qc * gy - q3 * gz);
+ q1 += (qa * gx + qc * gz - q3 * gy);
+ q2 += (qa * gy - qb * gz + q3 * gx);
+ q3 += (qa * gz + qb * gy - qc * gx);
+
+ // Normalise quaternion
+ recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+ q0 *= recipNorm;
+ q1 *= recipNorm;
+ q2 *= recipNorm;
+ q3 *= recipNorm;
+}
+
+/*
+ * [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
+
+ 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};
+
+ // 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));
+ 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();
+
+ MahonyAHRSupdate(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);
+
+ float aSq = q0*q0;
+ float bSq = q1*q1;
+ float cSq = q2*q2;
+ float dSq = q3*q3;
+
+ Rot_matrix[0] = aSq + bSq - cSq - dSq;
+ Rot_matrix[1] = 2.0 * (b * c - a * d);
+ Rot_matrix[2] = 2.0 * (a * c + b * d);
+ Rot_matrix[3] = 2.0 * (b * c + a * d);
+ Rot_matrix[4] = aSq - bSq + cSq - dSq;
+ Rot_matrix[5] = 2.0 * (c * d - a * b);
+ Rot_matrix[6] = 2.0 * (b * d - a * c);
+ Rot_matrix[7] = 2.0 * (a * b + c * d);
+ Rot_matrix[8] = aSq - bSq - cSq + dSq;
+
+ /* Compute Euler angle */
+ float theta = asinf(-Rot_matrix[6]);
+ euler[1] = theta;
+
+ if(fabsf(theta - M_PI_2_F) < 1.0e-3f){
+ euler[0] = 0.0f;
+ euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]);
+ } else if (fabsf(theta + M_PI_2_F) < 1.0e-3f) {
+ euler[0] = 0.0f;
+ euler[2] = atan2f(Rot_matrix[5] - Rot_matrix[1], Rot_matrix[2] + Rot_matrix[4] - euler[0]);
+ } else {
+ euler[0] = atan2f(Rot_matrix[7], Rot_matrix[8]);
+ euler[2] = atan2f(Rot_matrix[3], Rot_matrix[0]);
+ }
+
+ /* 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;
+
+ /* FIXME : This can be a problem for rate controller. Rate in body or inertial?
+ att.rollspeed = x_aposteriori[0];
+ att.pitchspeed = x_aposteriori[1];
+ att.yawspeed = x_aposteriori[2];
+ att.rollacc = x_aposteriori[3];
+ att.pitchacc = x_aposteriori[4];
+ att.yawacc = x_aposteriori[5];
+ */
+
+ //att.yawspeed =z_k[2] ;
+ /* copy offsets */
+ //memcpy(&att.rate_offsets, &(x_aposteriori[3]), 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);
+ }
+ }
+ }
+
+ loopcounter++;
+ }
+
+ thread_running = false;
+
+ 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..bf0f49db8
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.c
@@ -0,0 +1,44 @@
+/*
+ * @file attitude_estimator_so3_comp_params.c
+ *
+ * Parameters for SO3 complementary filter
+ */
+
+#include "attitude_estimator_so3_comp_params.h"
+
+/* This is filter gain for nonlinear SO3 complementary filter */
+PARAM_DEFINE_FLOAT(SO3_COMP_KP, 1.0f);
+PARAM_DEFINE_FLOAT(SO3_COMP_KI, 0.0f);
+
+/* 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_ekf_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_ekf_param_handles *h, struct attitude_estimator_ekf_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..2fccec61c
--- /dev/null
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_params.h
@@ -0,0 +1,32 @@
+/*
+ * @file attitude_estimator_so3_comp_params.h
+ *
+ * Parameters for EKF filter
+ */
+
+#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