mirror of
https://gitlab.freedesktop.org/monado/monado.git
synced 2025-02-01 03:18:26 +00:00
t/psmv: Use new imu fusion in psmv positional tracking.
This commit is contained in:
parent
18f9760986
commit
430e27d084
|
@ -13,6 +13,7 @@
|
||||||
#include "tracking/t_tracking.h"
|
#include "tracking/t_tracking.h"
|
||||||
#include "tracking/t_calibration_opencv.h"
|
#include "tracking/t_calibration_opencv.h"
|
||||||
#include "tracking/t_fusion.h"
|
#include "tracking/t_fusion.h"
|
||||||
|
#include "tracking/t_imu_fusion.h"
|
||||||
|
|
||||||
#include "util/u_var.h"
|
#include "util/u_var.h"
|
||||||
#include "util/u_misc.h"
|
#include "util/u_misc.h"
|
||||||
|
@ -97,6 +98,8 @@ struct TrackerPSMV
|
||||||
State filter_state;
|
State filter_state;
|
||||||
ProcessModel process_model;
|
ProcessModel process_model;
|
||||||
|
|
||||||
|
xrt_fusion::SimpleIMUFusion imu;
|
||||||
|
|
||||||
xrt_vec3 tracked_object_position;
|
xrt_vec3 tracked_object_position;
|
||||||
Eigen::Isometry3f room_transform;
|
Eigen::Isometry3f room_transform;
|
||||||
};
|
};
|
||||||
|
@ -455,14 +458,14 @@ imu_data(TrackerPSMV &t,
|
||||||
}
|
}
|
||||||
|
|
||||||
float dt = time_ns_to_s(delta_ns);
|
float dt = time_ns_to_s(delta_ns);
|
||||||
// Super simple fusion.
|
t.imu.handleAccel(map_vec3(sample->accel_m_s2).cast<double>(), dt);
|
||||||
math_quat_integrate_velocity(&t.fusion.rot, &sample->gyro_rad_secs, dt,
|
t.imu.handleGyro(map_vec3(sample->gyro_rad_secs).cast<double>(), dt);
|
||||||
&t.fusion.rot);
|
t.imu.postCorrect();
|
||||||
|
|
||||||
//! @todo use better measurements instead of the above "simple fusion"
|
//! @todo use better measurements instead of the above "simple fusion"
|
||||||
flexkalman::predict(t.filter_state, t.process_model, dt);
|
flexkalman::predict(t.filter_state, t.process_model, dt);
|
||||||
Eigen::Quaterniond quat = Eigen::Quaternionf(map_quat(t.fusion.rot)).cast<double>();
|
|
||||||
auto meas = flexkalman::AbsoluteOrientationMeasurement{
|
auto meas = flexkalman::AbsoluteOrientationMeasurement{
|
||||||
quat, Eigen::Vector3d::Constant(0.01)};
|
t.imu.getQuat(), Eigen::Vector3d::Constant(0.01)};
|
||||||
if (!flexkalman::correctUnscented(t.filter_state, meas)) {
|
if (!flexkalman::correctUnscented(t.filter_state, meas)) {
|
||||||
fprintf(stderr,
|
fprintf(stderr,
|
||||||
"Got non-finite something when filtering IMU!\n");
|
"Got non-finite something when filtering IMU!\n");
|
||||||
|
|
Loading…
Reference in a new issue