aboutsummaryrefslogtreecommitdiff
path: root/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp')
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp173
1 files changed, 138 insertions, 35 deletions
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index a70a14fe4..35dc39ec6 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012-2014 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
@@ -34,9 +32,12 @@
****************************************************************************/
/*
- * @file attitude_estimator_ekf_main.c
+ * @file attitude_estimator_ekf_main.cpp
*
* Extended Kalman Filter for Attitude Estimation.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
@@ -58,9 +59,14 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h>
+#include <lib/mathlib/mathlib.h>
+#include <lib/geo/geo.h>
+
#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -107,7 +113,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_create().
+ * to task_spawn_cmd().
*/
int attitude_estimator_ekf_main(int argc, char *argv[])
{
@@ -214,6 +220,10 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
struct sensor_combined_s raw;
memset(&raw, 0, sizeof(raw));
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_pos));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_control_mode_s control_mode;
@@ -221,12 +231,32 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
uint64_t last_data = 0;
uint64_t last_measurement = 0;
+ uint64_t last_vel_t = 0;
+
+ /* current velocity */
+ math::Vector<3> vel;
+ vel.zero();
+ /* previous velocity */
+ math::Vector<3> vel_prev;
+ vel_prev.zero();
+ /* actual acceleration (by GPS velocity) in body frame */
+ math::Vector<3> acc;
+ acc.zero();
+ /* rotation matrix */
+ math::Matrix<3, 3> R;
+ R.identity();
/* subscribe to raw data */
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
/* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */
orb_set_interval(sub_raw, 3);
+ /* subscribe to GPS */
+ int sub_gps = orb_subscribe(ORB_ID(vehicle_gps_position));
+
+ /* subscribe to GPS */
+ int sub_global_pos = orb_subscribe(ORB_ID(vehicle_global_position));
+
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
@@ -237,7 +267,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
- int printcounter = 0;
thread_running = true;
@@ -245,11 +274,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
// 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_ekf_params ekf_params;
@@ -259,11 +284,16 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* initialize parameter handles */
parameters_init(&ekf_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;
+
+ /* magnetic declination, in radians */
+ float mag_decl = 0.0f;
+
+ /* rotation matrix for magnetic declination */
+ math::Matrix<3, 3> R_decl;
+ R_decl.identity();
/* register the perf counter */
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");
@@ -307,6 +337,25 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* get latest measurements */
orb_copy(ORB_ID(sensor_combined), sub_raw, &raw);
+ bool gps_updated;
+ orb_check(sub_gps, &gps_updated);
+ if (gps_updated) {
+ orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps);
+
+ if (gps.eph < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
+ mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
+
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, mag_decl);
+ }
+ }
+
+ bool global_pos_updated;
+ orb_check(sub_global_pos, &global_pos_updated);
+ if (global_pos_updated) {
+ orb_copy(ORB_ID(vehicle_global_position), sub_global_pos, &global_pos);
+ }
+
if (!initialized) {
// XXX disabling init for now
initialized = true;
@@ -333,10 +382,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
uint8_t update_vect[3] = {0, 0, 0};
/* Fill in gyro measurements */
- if (sensor_last_count[0] != raw.gyro_counter) {
+ if (sensor_last_timestamp[0] != raw.timestamp) {
update_vect[0] = 1;
- sensor_last_count[0] = raw.gyro_counter;
- sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
+ // sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -345,23 +393,62 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
z_k[2] = raw.gyro_rad_s[2] - gyro_offsets[2];
/* update accelerometer measurements */
- if (sensor_last_count[1] != raw.accelerometer_counter) {
+ if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
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;
+ // sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
+ sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
- z_k[3] = raw.accelerometer_m_s2[0];
- z_k[4] = raw.accelerometer_m_s2[1];
- z_k[5] = raw.accelerometer_m_s2[2];
+ hrt_abstime vel_t = 0;
+ bool vel_valid = false;
+ if (ekf_params.acc_comp == 1 && gps.fix_type >= 3 && gps.eph < 10.0f && gps.vel_ned_valid && hrt_absolute_time() < gps.timestamp_velocity + 500000) {
+ vel_valid = true;
+ if (gps_updated) {
+ vel_t = gps.timestamp_velocity;
+ vel(0) = gps.vel_n_m_s;
+ vel(1) = gps.vel_e_m_s;
+ vel(2) = gps.vel_d_m_s;
+ }
+
+ } else if (ekf_params.acc_comp == 2 && gps.eph < 5.0f && global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
+ vel_valid = true;
+ if (global_pos_updated) {
+ vel_t = global_pos.timestamp;
+ vel(0) = global_pos.vel_n;
+ vel(1) = global_pos.vel_e;
+ vel(2) = global_pos.vel_d;
+ }
+ }
+
+ if (vel_valid) {
+ /* velocity is valid */
+ if (vel_t != 0) {
+ /* velocity updated */
+ if (last_vel_t != 0 && vel_t != last_vel_t) {
+ float vel_dt = (vel_t - last_vel_t) / 1000000.0f;
+ /* calculate acceleration in body frame */
+ acc = R.transposed() * ((vel - vel_prev) / vel_dt);
+ }
+ last_vel_t = vel_t;
+ vel_prev = vel;
+ }
+
+ } else {
+ /* velocity is valid, reset acceleration */
+ acc.zero();
+ vel_prev.zero();
+ last_vel_t = 0;
+ }
+
+ z_k[3] = raw.accelerometer_m_s2[0] - acc(0);
+ z_k[4] = raw.accelerometer_m_s2[1] - acc(1);
+ z_k[5] = raw.accelerometer_m_s2[2] - acc(2);
/* update magnetometer measurements */
- if (sensor_last_count[2] != raw.magnetometer_counter) {
+ if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
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;
+ // sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
+ sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
z_k[6] = raw.magnetometer_ga[0];
@@ -389,6 +476,17 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
dt = 0.005f;
parameters_update(&ekf_param_handles, &ekf_params);
+ /* update mag declination rotation matrix */
+ if (gps.eph < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
+ mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
+
+ } else {
+ mag_decl = ekf_params.mag_decl;
+ }
+
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, mag_decl);
+
x_aposteriori_k[0] = z_k[0];
x_aposteriori_k[1] = z_k[1];
x_aposteriori_k[2] = z_k[2];
@@ -410,8 +508,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- uint64_t timing_start = hrt_absolute_time();
-
attitudeKalmanfilter(update_vect, dt, z_k, x_aposteriori_k, P_aposteriori_k, ekf_params.q, ekf_params.r,
euler, Rot_matrix, x_aposteriori, P_aposteriori);
@@ -425,7 +521,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- if (last_data > 0 && raw.timestamp - last_data > 12000)
+ if (last_data > 0 && raw.timestamp - last_data > 30000)
printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
last_data = raw.timestamp;
@@ -433,10 +529,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* send out */
att.timestamp = raw.timestamp;
- // XXX Apply the same transformation to the rotation matrix
- att.roll = euler[0] - ekf_params.roll_off;
- att.pitch = euler[1] - ekf_params.pitch_off;
- att.yaw = euler[2] - ekf_params.yaw_off;
+ att.roll = euler[0];
+ att.pitch = euler[1];
+ att.yaw = euler[2] + mag_decl;
att.rollspeed = x_aposteriori[0];
att.pitchspeed = x_aposteriori[1];
@@ -445,12 +540,20 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
att.pitchacc = x_aposteriori[4];
att.yawacc = x_aposteriori[5];
- //att.yawspeed =z_k[2] ;
+ att.g_comp[0] = raw.accelerometer_m_s2[0] - acc(0);
+ att.g_comp[1] = raw.accelerometer_m_s2[1] - acc(1);
+ att.g_comp[2] = raw.accelerometer_m_s2[2] - acc(2);
+
/* copy offsets */
memcpy(&att.rate_offsets, &(x_aposteriori[3]), sizeof(att.rate_offsets));
+ /* magnetic declination */
+
+ math::Matrix<3, 3> R_body = (&Rot_matrix[0]);
+ R = R_decl * R_body;
+
/* copy rotation matrix */
- memcpy(&att.R, Rot_matrix, sizeof(Rot_matrix));
+ memcpy(&att.R[0][0], &R.data[0][0], sizeof(att.R));
att.R_valid = true;
if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) {