aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-03-24 09:35:47 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-03-24 09:35:47 +0100
commit0874507a44347d10e10606061c411f0b0129dc5b (patch)
tree7c2f0fcce2e0a6656a6fe37d66e3f514824c75ec
parentd64c861ef84c6f1539dbb7cb1e5a5fd11e9f2656 (diff)
downloadpx4-firmware-0874507a44347d10e10606061c411f0b0129dc5b.tar.gz
px4-firmware-0874507a44347d10e10606061c411f0b0129dc5b.tar.bz2
px4-firmware-0874507a44347d10e10606061c411f0b0129dc5b.zip
Added estimator status logging to sdlog2
-rw-r--r--src/modules/sdlog2/sdlog2.c18
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h11
-rw-r--r--src/modules/uORB/topics/estimator_status.h1
3 files changed, 29 insertions, 1 deletions
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index ad709d27d..3f07eea53 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -83,6 +83,7 @@
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/telemetry_status.h>
+#include <uORB/topics/estimator_status.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -794,6 +795,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct battery_status_s battery;
struct telemetry_status_s telemetry;
struct range_finder_report range_finder;
+ struct estimator_status_report estimator_status;
} buf;
memset(&buf, 0, sizeof(buf));
@@ -825,6 +827,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_BATT_s log_BATT;
struct log_DIST_s log_DIST;
struct log_TELE_s log_TELE;
+ struct log_ESTM_s log_ESTM;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -855,6 +858,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int battery_sub;
int telemetry_sub;
int range_finder_sub;
+ int estimator_status_sub;
} subs;
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
@@ -879,6 +883,7 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
+ subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status));
thread_running = true;
@@ -1243,6 +1248,19 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(DIST);
}
+ /* --- ESTIMATOR STATUS --- */
+ if (copy_if_updated(ORB_ID(estimator_status), subs.estimator_status_sub, &buf.estimator_status)) {
+ log_msg.msg_type = LOG_ESTM_MSG;
+ unsigned maxcopy = (sizeof(buf.estimator_status.states) < sizeof(log_msg.body.log_ESTM.s)) ? sizeof(buf.estimator_status.states) : sizeof(log_msg.body.log_ESTM.s);
+ memset(&(log_msg.body.log_ESTM.s), 0, sizeof(log_msg.body.log_ESTM.s));
+ memcpy(&(log_msg.body.log_ESTM.s), buf.estimator_status.states, maxcopy);
+ log_msg.body.log_ESTM.n_states = buf.estimator_status.n_states;
+ log_msg.body.log_ESTM.states_nan = buf.estimator_status.states_nan;
+ log_msg.body.log_ESTM.covariance_nan = buf.estimator_status.covariance_nan;
+ log_msg.body.log_ESTM.kalman_gain_nan = buf.estimator_status.kalman_gain_nan;
+ LOGBUFFER_WRITE_AND_COUNT(DIST);
+ }
+
/* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
/* only request write if several packets can be written at once */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index fe500ad5f..2b41755de 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -299,6 +299,16 @@ struct log_PARM_s {
float value;
};
+/* --- ESTM - ESTIMATOR STATUS --- */
+#define LOG_ESTM_MSG 132
+struct log_ESTM_s {
+ float s[32];
+ uint8_t n_states;
+ uint8_t states_nan;
+ uint8_t covariance_nan;
+ uint8_t kalman_gain_nan;
+};
+
#pragma pack(pop)
/* construct list of all message formats */
@@ -331,6 +341,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(TIME, "Q", "StartTime"),
LOG_FORMAT(VER, "NZ", "Arch,FwGit"),
LOG_FORMAT(PARM, "Nf", "Name,Value"),
+ LOG_FORMAT(ESTM, "ffffffffffffffffffffffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27,s28,s29,s30,s31,n_states,states_nan,cov_nan,kgain_nan"),
};
static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);
diff --git a/src/modules/uORB/topics/estimator_status.h b/src/modules/uORB/topics/estimator_status.h
index 66ca03019..5530cdb21 100644
--- a/src/modules/uORB/topics/estimator_status.h
+++ b/src/modules/uORB/topics/estimator_status.h
@@ -67,7 +67,6 @@ struct estimator_status_report {
bool states_nan; /**< If set to true, one of the states is NaN */
bool covariance_nan; /**< If set to true, the covariance matrix went NaN */
bool kalman_gain_nan; /**< If set to true, the Kalman gain matrix went NaN */
- bool states_out_of_bounds; /**< If set to true, one of the states is out of bounds */
};