aboutsummaryrefslogtreecommitdiff
path: root/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-29 08:00:12 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-29 08:00:12 +0100
commitf4e0dc2857da7a8b42b7439ae57310b23c902cd9 (patch)
treed31b6697458c5f54672ea6b5bbc3a267e6fa1be5 /src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
parentacb4844939f971a1a33515316f5e6c7c8f668f12 (diff)
parent22f744f0e17f83a706998381d1977c9cb24d457a (diff)
downloadpx4-firmware-f4e0dc2857da7a8b42b7439ae57310b23c902cd9.tar.gz
px4-firmware-f4e0dc2857da7a8b42b7439ae57310b23c902cd9.tar.bz2
px4-firmware-f4e0dc2857da7a8b42b7439ae57310b23c902cd9.zip
Merge remote-tracking branch 'upstream/master' into dev_ros
Conflicts: .gitmodules
Diffstat (limited to 'src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp')
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp50
1 files changed, 37 insertions, 13 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 4c64c88ae..d68f12c8e 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -63,6 +63,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <drivers/drv_hrt.h>
#include <lib/mathlib/mathlib.h>
@@ -134,7 +135,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
7200,
attitude_estimator_ekf_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
@@ -207,7 +208,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
}; /**< init: identity matrix */
float debugOutput[4] = { 0.0f };
-
int overloadcounter = 19;
/* Initialize filter */
@@ -220,6 +220,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
memset(&raw, 0, sizeof(raw));
struct vehicle_gps_position_s gps;
memset(&gps, 0, sizeof(gps));
+ gps.eph = 100000;
+ gps.epv = 100000;
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
struct vehicle_attitude_s att;
@@ -258,9 +260,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
- /* subscribe to control mode*/
+ /* subscribe to control mode */
int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
+ /* subscribe to vision estimate */
+ int vision_sub = orb_subscribe(ORB_ID(vision_position_estimate));
+
/* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
@@ -268,14 +273,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
thread_running = true;
- /* advertise debug value */
- // struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
- // orb_advert_t pub_dbg = -1;
-
/* keep track of sensor updates */
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
- struct attitude_estimator_ekf_params ekf_params = { 0 };
+ struct attitude_estimator_ekf_params ekf_params;
+ memset(&ekf_params, 0, sizeof(ekf_params));
struct attitude_estimator_ekf_param_handles ekf_param_handles = { 0 };
@@ -293,6 +295,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
math::Matrix<3, 3> R_decl;
R_decl.identity();
+ struct vision_position_estimate vision {};
+
/* register the perf counter */
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");
@@ -313,8 +317,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_copy(ORB_ID(vehicle_control_mode), sub_control_mode, &control_mode);
if (!control_mode.flag_system_hil_enabled) {
- fprintf(stderr,
- "[att ekf] WARNING: Not getting sensors - sensor app running?\n");
+ warnx("WARNING: Not getting sensors - sensor app running?");
}
} else {
@@ -449,9 +452,30 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
- z_k[6] = raw.magnetometer_ga[0];
- z_k[7] = raw.magnetometer_ga[1];
- z_k[8] = raw.magnetometer_ga[2];
+ bool vision_updated = false;
+ orb_check(vision_sub, &vision_updated);
+
+ if (vision_updated) {
+ orb_copy(ORB_ID(vision_position_estimate), vision_sub, &vision);
+ }
+
+ if (vision.timestamp_boot > 0 && (hrt_elapsed_time(&vision.timestamp_boot) < 500000)) {
+
+ math::Quaternion q(vision.q);
+ math::Matrix<3, 3> Rvis = q.to_dcm();
+
+ math::Vector<3> v(1.0f, 0.0f, 0.4f);
+
+ math::Vector<3> vn = Rvis * v;
+
+ z_k[6] = vn(0);
+ z_k[7] = vn(1);
+ z_k[8] = vn(2);
+ } else {
+ z_k[6] = raw.magnetometer_ga[0];
+ z_k[7] = raw.magnetometer_ga[1];
+ z_k[8] = raw.magnetometer_ga[2];
+ }
uint64_t now = hrt_absolute_time();
unsigned int time_elapsed = now - last_run;