aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-03-24 09:04:35 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-03-24 09:04:35 +0100
commit01f33df70718b7a7dba342fb5920d91b3cd83c09 (patch)
tree05fd21d12f0ab996eaf7499e012f0584be3e2650 /src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
parent43a672988dca59b9313482996773389cb67c5b1d (diff)
downloadpx4-firmware-01f33df70718b7a7dba342fb5920d91b3cd83c09.tar.gz
px4-firmware-01f33df70718b7a7dba342fb5920d91b3cd83c09.tar.bz2
px4-firmware-01f33df70718b7a7dba342fb5920d91b3cd83c09.zip
Added EKF filter health status reporting, added dynamic in-air reset.
Diffstat (limited to 'src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp')
-rw-r--r--src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp65
1 files changed, 64 insertions, 1 deletions
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
index e46dffde3..e75b844fd 100644
--- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
@@ -71,6 +71,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/estimator_status.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
@@ -144,6 +145,7 @@ private:
orb_advert_t _att_pub; /**< vehicle attitude */
orb_advert_t _global_pos_pub; /**< global position */
orb_advert_t _local_pos_pub; /**< position in local frame */
+ orb_advert_t _estimator_status_pub; /**< status of the estimator */
struct vehicle_attitude_s _att; /**< vehicle attitude */
struct gyro_report _gyro;
@@ -260,6 +262,7 @@ FixedwingEstimator::FixedwingEstimator() :
_att_pub(-1),
_global_pos_pub(-1),
_local_pos_pub(-1),
+ _estimator_status_pub(-1),
_baro_ref(0.0f),
_baro_gps_offset(0.0f),
@@ -701,7 +704,67 @@ FixedwingEstimator::task_main()
/**
* CHECK IF THE INPUT DATA IS SANE
*/
- CheckAndBound();
+ int check = CheckAndBound();
+
+ switch (check) {
+ case 0:
+ /* all ok */
+ break;
+ case 1:
+ {
+ const char* str = "NaN in states, resetting";
+ warnx(str);
+ mavlink_log_critical(_mavlink_fd, str);
+ break;
+ }
+ case 2:
+ {
+ const char* str = "stale IMU data, resetting";
+ warnx(str);
+ mavlink_log_critical(_mavlink_fd, str);
+ break;
+ }
+ case 3:
+ {
+ const char* str = "switching dynamic / static state";
+ warnx(str);
+ mavlink_log_critical(_mavlink_fd, str);
+ break;
+ }
+ }
+
+ // If non-zero, we got a problem
+ if (check) {
+
+ struct ekf_status_report ekf_report;
+
+ GetLastErrorState(&ekf_report);
+
+ struct estimator_status_report rep;
+ memset(&rep, 0, sizeof(rep));
+ rep.timestamp = hrt_absolute_time();
+
+ rep.states_nan = ekf_report.statesNaN;
+ rep.covariance_nan = ekf_report.covarianceNaN;
+ rep.kalman_gain_nan = ekf_report.kalmanGainsNaN;
+
+ // Copy all states or at least all that we can fit
+ int i = 0;
+ unsigned ekf_n_states = (sizeof(ekf_report.states) / sizeof(ekf_report.states[0]));
+ unsigned max_states = (sizeof(rep.states) / sizeof(rep.states[0]));
+ rep.n_states = (ekf_n_states < max_states) ? ekf_n_states : max_states;
+
+ while ((i < ekf_n_states) && (i < max_states)) {
+
+ rep.states[i] = ekf_report.states[i];
+ }
+
+ if (_estimator_status_pub > 0) {
+ orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &rep);
+ } else {
+ _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &rep);
+ }
+ }
/**