ethzasl-msf - Modular Sensor Fusion
Time delay compensated single and multi sensor fusion framework based on an EKF
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
msf_core.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2013 Simon Lynen, ASL, ETH Zurich, Switzerland
3  * You can contact the author at <slynen at ethz dot ch>
4  * Copyright (C) 2011-2012 Stephan Weiss, ASL, ETH Zurich, Switzerland
5  * You can contact the author at <stephan dot weiss at ieee dot org>
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * http://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  */
19 #include <chrono>
20 #include <thread>
21 #include <deque>
22 #include <numeric>
23 #include <string>
24 #include <vector>
25 
26 #include <msf_timing/Timer.h>
28 #include <msf_core/eigen_utils.h>
30 #include <msf_core/msf_tools.h>
32 #include <msf_core/falsecolor.h>
33 #include <msf_core/msf_types.hpp>
34 
35 namespace msf_core {
36 template<typename EKFState_T>
38  : usercalc_(usercalc) { // The interface for the user to customize EKF
39  // interna, DO ABSOLUTELY NOT USE THIS POINTER INSIDE THIS CTOR!!
40 
41  // Set the output precision for numeric values.
42  std::setprecision(NUMERIC_PREC);
43  initialized_ = false;
44  predictionMade_ = false;
45  isfuzzyState_ = false;
46  g_ << 0, 0, 9.80834; // At 47.37 lat (Zurich).
49 }
50 
51 template<typename EKFState_T>
53 }
54 
55 template<typename EKFState_T>
57  Eigen::Matrix<double, EKFState_T::nErrorStatesAtCompileTime,
58  EKFState_T::nErrorStatesAtCompileTime>& P) {
59  enum {
60  // We might want to calculate this, but on the other hand the values for the
61  // matrix later on are anyway hardcoded.
62  coreErrorStates = 15
63  };
64  P.setIdentity();
65  P *= 0.0001; // Set diagonal small covariance for all states.
66 
67  // Now set the core state covariance to the simulated values.
68  Eigen::Matrix<double, coreErrorStates, coreErrorStates> P_core;
69  // This violates the 80 chars rule, to keep it somehow readable.
70  P_core << 0.0166, 0.0122, -0.0015, 0.0211, 0.0074, 0.0000, 0.0012, -0.0012, 0.0001, -0.0000, 0.0000, -0.0000, -0.0003, -0.0002, -0.0000,
71  0.0129, 0.0508, -0.0020, 0.0179, 0.0432, 0.0006, 0.0020, 0.0004, -0.0002, -0.0000, 0.0000, 0.0000, 0.0003, -0.0002, 0.0000,
72  -0.0013, -0.0009, 0.0142, -0.0027, 0.0057, 0.0079, 0.0007, 0.0007, 0.0000, -0.0000, -0.0000, 0.0000, -0.0001, -0.0004, -0.0001,
73  0.0210, 0.0162, -0.0026, 0.0437, 0.0083, -0.0017, 0.0016, -0.0021, -0.0014, -0.0000, 0.0000, 0.0000, 0.0003, -0.0001, 0.0000,
74  0.0093, 0.0461, 0.0036, 0.0153, 0.0650, -0.0016, 0.0025, 0.0013, -0.0000, -0.0000, 0.0000, 0.0000, 0.0003, 0.0002, 0.0000,
75  -0.0000, 0.0005, 0.0080, -0.0019, -0.0021, 0.0130, 0.0001, 0.0001, 0.0000, -0.0000, 0.0000, -0.0000, -0.0003, 0.0001, -0.0001,
76  0.0012, 0.0024, 0.0006, 0.0017, 0.0037, 0.0001, 0.0005, 0.0000, 0.0001, -0.0000, 0.0000, -0.0000, -0.0000, -0.0001, -0.0000,
77  -0.0011, 0.0008, 0.0007, -0.0023, 0.0019, 0.0001, 0.0000, 0.0005, -0.0001, -0.0000, -0.0000, 0.0000, 0.0001, -0.0001, -0.0000,
78  0.0001, -0.0002, -0.0000, -0.0014, 0.0001, 0.0000, 0.0000, -0.0001, 0.0006, -0.0000, -0.0000, -0.0000, 0.0000, 0.0000, -0.0000,
79  -0.0000, -0.0000, -0.0000, -0.0000, -0.0000, -0.0000, -0.0000, -0.0000, -0.0000, 0.0000, -0.0000, 0.0000, 0.0000, 0.0000, 0.0000,
80  0.0000, 0.0000, -0.0000, 0.0000, 0.0000, 0.0000, 0.0000, -0.0000, -0.0000, -0.0000, 0.0000, -0.0000, 0.0000, 0.0000, 0.0000,
81  -0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, -0.0000, 0.0000, -0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, -0.0000,
82  -0.0003, 0.0003, -0.0001, 0.0003, 0.0003, -0.0003, -0.0000, 0.0001, 0.0000, 0.0000, 0.0000, 0.0000, 0.0010, 0.0000, 0.0000,
83  -0.0002, -0.0002, -0.0004, -0.0001, 0.0003, 0.0001, -0.0001, -0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0010, 0.0000,
84  -0.0000, 0.0000, -0.0001, 0.0000, 0.0000, -0.0001, -0.0000, -0.0000, -0.0000, 0.0000, 0.0000, -0.0000, 0.0000, 0.0000, 0.0001;
85 
86  P_core = 0.5 * (P_core + P_core.transpose());
87  P.template block<coreErrorStates, coreErrorStates>(0, 0) = P_core;
88 }
89 
90 template<typename EKFState_T>
92  return usercalc_;
93 }
94 
95 template<typename EKFState_T>
97  const msf_core::Vector3& linear_acceleration,
98  const msf_core::Vector3& angular_velocity, const double& msg_stamp,
99  size_t msg_seq) {
100 
101  if (!initialized_)
102  return;
103 
104  msf_timing::DebugTimer timer_PropgetClosestState("PropgetClosestState");
105  if (it_last_IMU == stateBuffer_.getIteratorEnd()) {
106  it_last_IMU = stateBuffer_.getIteratorClosestBefore(msg_stamp);
107  }
108 
109  shared_ptr<EKFState_T> lastState = it_last_IMU->second;
110  timer_PropgetClosestState.Stop();
111 
112  msf_timing::DebugTimer timer_PropPrepare("PropPrepare");
113  if (lastState->time == -1) {
115  2, __FUNCTION__<<"ImuCallback: closest state is invalid\n");
116  return; // Early abort.
117  }
118 
119  shared_ptr<EKFState_T> currentState(new EKFState_T);
120  currentState->time = msg_stamp;
121 
122  // Check if this IMU message is really after the last one (caused by restarting
123  // a bag file).
124  if (currentState->time - lastState->time < -0.01 && predictionMade_) {
125  initialized_ = false;
126  predictionMade_ = false;
128  __FUNCTION__<<"latest IMU message was out of order by a too large amount, "
129  "resetting EKF: last-state-time: " << msf_core::timehuman(lastState->time) << " "<< "current-imu-time: "<< msf_core::timehuman(currentState->time));
130  return;
131  }
132 
133  static int seq = 0;
134  // Get inputs.
135  currentState->a_m = linear_acceleration;
136  currentState->w_m = angular_velocity;
137 
138  // Remove acc spikes (TODO (slynen): find a cleaner way to do this).
139  static Eigen::Matrix<double, 3, 1> last_am = Eigen::Matrix<double, 3, 1>(0, 0,
140  0);
141  if (currentState->a_m.norm() > 50)
142  currentState->a_m = last_am;
143  else {
144  // Try to get the state before the current time.
145  if (lastState->time == -1) {
147  "Accelerometer readings had a spike, but no prior state was in the "
148  "buffer to take cleaner measurements from");
149  return;
150  }
151  last_am = lastState->a_m;
152  }
153  if (!predictionMade_) {
154  if (lastState->time == -1) {
155  MSF_WARN_STREAM("Wanted to compare prediction time offset to last state, "
156  "but no prior state was in the buffer to take cleaner measurements from");
157  return;
158  }
159  if (fabs(currentState->time - lastState->time) > 0.1) {
161  2, "large time-gap re-initializing to last state\n");
162  typename StateBuffer_T::Ptr_T tmp = stateBuffer_.updateTime(
163  lastState->time, currentState->time);
164  time_P_propagated = currentState->time;
165  return; // // early abort // // (if timegap too big)
166  }
167  }
168 
169  if (lastState->time == -1) {
171  "Wanted to propagate state, but no valid prior state could be found in "
172  "the buffer");
173  return;
174  }
175  timer_PropPrepare.Stop();
176 
177  msf_timing::DebugTimer timer_PropState("PropState");
178  //propagate state and covariance
179  propagateState(lastState, currentState);
180  timer_PropState.Stop();
181  msf_timing::DebugTimer timer_PropCov("PropCov");
182  propagatePOneStep();
183  timer_PropCov.Stop();
184 
185  usercalc_.publishStateAfterPropagation(currentState);
186 
187  // Making sure we have sufficient states to apply measurements to.
188  if (stateBuffer_.size() > 3)
189  predictionMade_ = true;
190 
191  msf_timing::DebugTimer timer_PropInsertState("PropInsertState");
192  it_last_IMU = stateBuffer_.insert(currentState);
193  timer_PropInsertState.Stop();
194 
195  if (predictionMade_) {
196  // Check if we can apply some pending measurement.
197  handlePendingMeasurements();
198  }
199  seq++;
200 
201 }
202 
203 template<typename EKFState_T>
205  const msf_core::Vector3& linear_acceleration,
206  const msf_core::Vector3& angular_velocity, const msf_core::Vector3& p,
207  const msf_core::Vector3& v, const msf_core::Quaternion& q,
208  bool is_already_propagated, const double& msg_stamp, size_t msg_seq) {
209 
210  if (!initialized_)
211  return;
212 
213  // fast method to get last_IMU is broken
214  // TODO(slynen): fix iterator setting for state callback
215 
216 // // Get the closest state and check validity.
217 // if (it_last_IMU == stateBuffer_.getIteratorEnd()) {
218 // it_last_IMU = stateBuffer_.getIteratorClosestBefore(msg_stamp);
219 // assert(!(it_last_IMU == stateBuffer_.getIteratorEnd()));
220 // }
221 
222  // TODO(slynen): not broken, revert back when it_last_IMU->second from above is fixed
223  shared_ptr<EKFState_T> lastState = stateBuffer_.getLast();//it_last_IMU->second;
224  if (lastState->time == -1) {
225  MSF_WARN_STREAM_THROTTLE(2, "StateCallback: closest state is invalid\n");
226  return; // Early abort.
227  }
228 
229  // Create a new state.
230  shared_ptr<EKFState_T> currentState(new EKFState_T);
231  currentState->time = msg_stamp;
232 
233  // Get inputs.
234  currentState->a_m = linear_acceleration;
235  currentState->w_m = angular_velocity;
236 
237  // Remove acc spikes (TODO (slynen): Find a cleaner way to do this).
238  static Eigen::Matrix<double, 3, 1> last_am = Eigen::Matrix<double, 3, 1>(0, 0,
239  0);
240  if (currentState->a_m.norm() > 50)
241  currentState->a_m = last_am;
242  else
243  last_am = currentState->a_m;
244 
245  if (!predictionMade_) {
246  if (fabs(currentState->time - lastState->time) > 5) {
247  typename StateBuffer_T::Ptr_T tmp = stateBuffer_.updateTime(
248  lastState->time, currentState->time);
250  2,
251  "large time-gap re-initializing to last state: " << msf_core::timehuman(tmp->time));
252  return; // Early abort (if timegap too big).
253  }
254  }
255 
256  bool isnumeric = checkForNumeric(
257  currentState->template get<StateDefinition_T::p>(),
258  "before prediction p");
259 
260  // State propagation is made externally, so we read the actual state.
261  if (is_already_propagated && isnumeric) {
262  currentState->template get<StateDefinition_T::p>() = p;
263  currentState->template get<StateDefinition_T::v>() = v;
264  currentState->template get<StateDefinition_T::q>() = q;
265 
266  // Zero props: copy non propagation states from last state.
267  boost::fusion::for_each(
268  currentState->statevars,
270 
271  } else if (!is_already_propagated || !isnumeric) {
272  // Otherwise let's do the state prop. here.
273  propagateState(lastState, currentState);
274  }
275 
276  propagatePOneStep();
277 
278  isnumeric = checkForNumeric(
279  currentState->template get<StateDefinition_T::p>(), "prediction p");
280  isnumeric = checkForNumeric(currentState->P, "prediction done P");
281 
282  // Clean reset of state and measurement buffer, before we start propagation.
283  if (!predictionMade_) {
284 
285  // Make sure we keep the covariance for the first state.
286  currentState->P = stateBuffer_.getLast()->P;
287  time_P_propagated = currentState->time;
288 
289  stateBuffer_.clear();
290  MeasurementBuffer_.clear();
291  while (!queueFutureMeasurements_.empty()) {
292  queueFutureMeasurements_.pop();
293  }
294  }
295  predictionMade_ = true;
296 
297  stateBuffer_.insert(currentState);
298  // Check if we can apply some pending measurement.
299  handlePendingMeasurements();
300 }
301 
302 template<typename EKFState_T>
304  if (queueFutureMeasurements_.empty())
305  return;
306  shared_ptr<MSF_MeasurementBase<EKFState_T> > meas = queueFutureMeasurements_
307  .front();
308  queueFutureMeasurements_.pop();
309  addMeasurement(meas);
310 }
311 
312 template<typename EKFState_T>
314  double timeold = 60; //1 min
315  stateBuffer_.clearOlderThan(timeold);
316  MeasurementBuffer_.clearOlderThan(timeold);
317 }
318 
319 template<typename EKFState_T>
320 void MSF_Core<EKFState_T>::propagateState(shared_ptr<EKFState_T>& state_old,
321  shared_ptr<EKFState_T>& state_new) {
322 
323  double dt = state_new->time - state_old->time;
324 
325  // Reset new state to zero.
326  boost::fusion::for_each(state_new->statevars, msf_tmp::resetState());
327 
328  // Zero props: copy constant for non propagated states.
329  boost::fusion::for_each(
330  state_new->statevars,
332 
333  Eigen::Matrix<double, 3, 1> dv;
334  const Vector3 ew = state_new->w_m
335  - state_new->template get<StateDefinition_T::b_w>();
336  const Vector3 ewold = state_old->w_m
337  - state_old->template get<StateDefinition_T::b_w>();
338  const Vector3 ea = state_new->a_m
339  - state_new->template get<StateDefinition_T::b_a>();
340  const Vector3 eaold = state_old->a_m
341  - state_old->template get<StateDefinition_T::b_a>();
342  const Matrix4 Omega = omegaMatJPL(ew);
343  const Matrix4 OmegaOld = omegaMatJPL(ewold);
344  Matrix4 OmegaMean = omegaMatJPL((ew + ewold) / 2);
345 
346  // Zero order quaternion integration.
347  // cur_state.q_ = (Eigen::Matrix<double,4,4>::Identity() +
348  // 0.5*Omega*dt)*StateBuffer_[(unsigned char)(idx_state_-1)].q_.coeffs();
349 
350  // First order quaternion integration, this is kind of costly and may not add
351  // a lot to the quality of propagation...
352  int div = 1;
353  Matrix4 MatExp;
354  MatExp.setIdentity();
355  OmegaMean *= 0.5 * dt;
356  for (int i = 1; i < 5; i++) { // Can be made fourth order or less to save cycles.
357  div *= i;
358  MatExp = MatExp + OmegaMean / div;
359  OmegaMean *= OmegaMean;
360  }
361 
362  // First oder quat integration matrix.
363  const Matrix4 quat_int = MatExp
364  + 1.0 / 48.0 * (Omega * OmegaOld - OmegaOld * Omega) * dt * dt;
365 
366  // First oder quaternion integration.
367  state_new->template get<StateDefinition_T::q>().coeffs() = quat_int *
368  state_old->template get<StateDefinition_T::q>().coeffs();
369  state_new->template get<StateDefinition_T::q>().normalize();
370 
371  dv = (state_new->template get<StateDefinition_T::q>().toRotationMatrix() *
372  ea + state_old-> template get<StateDefinition_T::q>().toRotationMatrix() *
373  eaold) / 2;
374  state_new->template get<StateDefinition_T::v>() = state_old
375  ->template get<StateDefinition_T::v>() + (dv - g_) * dt;
376  state_new->template get<StateDefinition_T::p>() = state_old
377  ->template get<StateDefinition_T::p>()
378  + ((state_new->template get<StateDefinition_T::v>()
379  + state_old->template get<StateDefinition_T::v>()) / 2 * dt);
380 }
381 
382 template<typename EKFState_T>
384  // Also propagate the covariance one step further, to distribute the
385  // processing load over time.
386  typename StateBuffer_T::iterator_T stateIteratorPLastPropagated = stateBuffer_
387  .getIteratorAtValue(time_P_propagated, false);
388  typename StateBuffer_T::iterator_T stateIteratorPLastPropagatedNext =
389  stateIteratorPLastPropagated;
390 
391  ++stateIteratorPLastPropagatedNext;
392  // Might happen if there is a measurement in the future.
393  if (stateIteratorPLastPropagatedNext != stateBuffer_.getIteratorEnd()) {
394 
395  predictProcessCovariance(stateIteratorPLastPropagated->second,
396  stateIteratorPLastPropagatedNext->second);
397 
398  if (!checkForNumeric(
399  stateIteratorPLastPropagatedNext->second
400  ->template get<StateDefinition_T::p>(),
401  "prediction p")) {
403  "prop state from:\t"<< stateIteratorPLastPropagated->second->toEigenVector());
405  "prop state to:\t"<< stateIteratorPLastPropagatedNext->second->toEigenVector());
406  MSF_ERROR_STREAM(__FUNCTION__<<" Resetting EKF");
407  predictionMade_ = initialized_ = false;
408  }
409  }
410 }
411 
412 template<typename EKFState_T>
414  const shared_ptr<EKFState_T>& state_old,
415  const shared_ptr<EKFState_T>& state_new,
418  typename StateBuffer_T::iterator_T it = stateBuffer_.getIteratorAtValue(
419  state_old);
420  typename StateBuffer_T::iterator_T itend = stateBuffer_.getIteratorAtValue(
421  state_new);
422  typedef Eigen::Matrix<double, MSF_Core<EKFState_T>::nErrorStatesAtCompileTime,
424  F = F_type::Identity();
425  for (; it != itend; ++it) {
426  F = F * it->second->Fd;
427  }
428 }
429 
430 template<typename EKFState_T>
432  shared_ptr<EKFState_T>& state_old, shared_ptr<EKFState_T>& state_new) {
433 
434  double dt = state_new->time - state_old->time;
435 
436  if (dt <= 0) {
438  1, "Requested cov prop between two states that where "<<dt<<" "
439  "seconds apart. Rejecting");
440  return;
441  }
442 
443  // Noises.
444  const Vector3 nav = Vector3::Constant(usercalc_.getParam_noise_acc());
445  const Vector3 nbav = Vector3::Constant(usercalc_.getParam_noise_accbias());
446 
447  const Vector3 nwv = Vector3::Constant(usercalc_.getParam_noise_gyr());
448  const Vector3 nbwv = Vector3::Constant(usercalc_.getParam_noise_gyrbias());
449 
450  // Bias corrected IMU readings.
451  const Vector3 ew = state_new->w_m
452  - state_new->template get<StateDefinition_T::b_w>();
453  const Vector3 ea = state_new->a_m
454  - state_new->template get<StateDefinition_T::b_a>();
455 
456  const Matrix3 a_sk = skew(ea);
457  const Matrix3 w_sk = skew(ew);
458  const Matrix3 eye3 = Eigen::Matrix<double, 3, 3>::Identity();
459 
460  const Matrix3 C_eq = state_new->template get<StateDefinition_T::q>().toRotationMatrix();
461 
462  const double dt_p2_2 = dt * dt * 0.5;
463  const double dt_p3_6 = dt_p2_2 * dt / 3.0;
464  const double dt_p4_24 = dt_p3_6 * dt * 0.25;
465  const double dt_p5_120 = dt_p4_24 * dt * 0.2;
466 
467  const Matrix3 Ca3 = C_eq * a_sk;
468  const Matrix3 A = Ca3
469  * (-dt_p2_2 * eye3 + dt_p3_6 * w_sk - dt_p4_24 * w_sk * w_sk);
470  const Matrix3 B = Ca3
471  * (dt_p3_6 * eye3 - dt_p4_24 * w_sk + dt_p5_120 * w_sk * w_sk);
472  const Matrix3 D = -A;
473  const Matrix3 E = eye3 - dt * w_sk + dt_p2_2 * w_sk * w_sk;
474  const Matrix3 F = -dt * eye3 + dt_p2_2 * w_sk - dt_p3_6 * (w_sk * w_sk);
475  const Matrix3 C = Ca3 * F;
476 
477  // Discrete error state propagation Matrix Fd according to:
478  // Stephan Weiss and Roland Siegwart.
479  // Real-Time Metric State Estimation for Modular Vision-Inertial Systems.
480  // IEEE International Conference on Robotics and Automation. Shanghai, China, 2011
481  typename EKFState_T::F_type& Fd = state_old->Fd;
482 
483  enum {
485  StateDefinition_T::p>::value,
486  idxstartcorr_v = msf_tmp::getStartIndexInCorrection<StateSequence_T,
487  StateDefinition_T::v>::value,
488  idxstartcorr_q = msf_tmp::getStartIndexInCorrection<StateSequence_T,
489  StateDefinition_T::q>::value,
490  idxstartcorr_b_w = msf_tmp::getStartIndexInCorrection<StateSequence_T,
491  StateDefinition_T::b_w>::value,
492  idxstartcorr_b_a = msf_tmp::getStartIndexInCorrection<StateSequence_T,
493  StateDefinition_T::b_a>::value
494  };
495 
496  Fd.template block<3, 3>(idxstartcorr_p, idxstartcorr_v) = dt * eye3;
497  Fd.template block<3, 3>(idxstartcorr_p, idxstartcorr_q) = A;
498  Fd.template block<3, 3>(idxstartcorr_p, idxstartcorr_b_w) = B;
499  Fd.template block<3, 3>(idxstartcorr_p, idxstartcorr_b_a) = -C_eq * dt_p2_2;
500 
501  Fd.template block<3, 3>(idxstartcorr_v, idxstartcorr_q) = C;
502  Fd.template block<3, 3>(idxstartcorr_v, idxstartcorr_b_w) = D;
503  Fd.template block<3, 3>(idxstartcorr_v, idxstartcorr_b_a) = -C_eq * dt;
504 
505  Fd.template block<3, 3>(idxstartcorr_q, idxstartcorr_q) = E;
506  Fd.template block<3, 3>(idxstartcorr_q, idxstartcorr_b_w) = F;
507 
508  typename EKFState_T::Q_type& Qd = state_old->Qd;
509 
510  calc_QCore<StateSequence_T, StateDefinition_T>(
511  dt, state_new->template get<StateDefinition_T::q>(), ew, ea, nav, nbav,
512  nwv, nbwv, Qd);
513 
514  // Call user Q calc to fill in the blocks of auxiliary states.
515  // TODO optim: make state Q-blocks map respective parts of Q using Eigen Map,
516  // avoids copy.
517  usercalc_.calculateQAuxiliaryStates(*state_new, dt);
518 
519  // Now copy the userdefined blocks to Qd.
520  boost::fusion::for_each(
521  state_new->statevars,
523 
524  // TODO (slynen) Optim: Multiplication of F blockwise, using the fact that aux
525  // states have no entries outside their block.
526  state_new->P = Fd * state_old->P * Fd.transpose() + Qd;
527 
528  // Set time for best cov prop to now.
529  time_P_propagated = state_new->time;
530 
531 }
532 
533 template<typename EKFState_T>
535  shared_ptr<MSF_MeasurementBase<EKFState_T> > measurement) {
536 
537  initialized_ = false;
538  predictionMade_ = false;
539 
540  usleep(100000); // Hack, Hack, Hack, Hack thread sync.
541 
542  MeasurementBuffer_.clear();
543  stateBuffer_.clear();
544  fuzzyTracker_.reset();
545 
546  while (!queueFutureMeasurements_.empty())
547  queueFutureMeasurements_.pop();
548 
549  // Push one state to the buffer to apply the init on.
550  shared_ptr<EKFState_T> state(new EKFState_T);
551  state->time = 0; // Will be set by the measurement.
552 
553  // Reset new state to zero.
554  boost::fusion::for_each(state->statevars, msf_tmp::resetState());
555 
556  // Set intialial covariance for core states.
557  setPCore(state->P);
558 
559  // Apply init measurement, where the user can provide additional values for P.
560  measurement->apply(state, *this);
561 
562  // Hack: Wait for the external propagation to get the init message.
563  usleep(10000);
564 
565  assert(state->time != 0);
566 
567  it_last_IMU = stateBuffer_.insert(state);
568 
569  // Will be set upon first IMU message.
570  time_P_propagated = state->time;
571 
572  MSF_INFO_STREAM("Initializing msf_core (built: " <<__DATE__<<")");
573 
574  // Echo params.
576  "Core parameters: "<<std::endl << "\tfixed_bias:\t" << usercalc_.getParam_fixed_bias() << std::endl << "\tfuzzythres:\t" << usercalc_.getParam_fuzzythres() << std::endl << "\tnoise_acc:\t" << usercalc_.getParam_noise_acc() << std::endl << "\tnoise_accbias:\t" << usercalc_.getParam_noise_accbias() << std::endl << "\tnoise_gyr:\t" << usercalc_.getParam_noise_gyr() << std::endl << "\tnoise_gyrbias:\t" << usercalc_.getParam_noise_gyrbias() << std::endl);
577 
578  MSF_INFO_STREAM("Core init with state: " << std::endl << state->print());
579  initialized_ = true;
580 
581  msf_timing::Timing::Print(std::cout);
582 }
583 
584 template<typename EKFState_T>
586  shared_ptr<MSF_MeasurementBase<EKFState_T> > measurement) {
587 
588  // Return if not initialized of no imu data available.
589  if (!initialized_ || !predictionMade_)
590  return;
591 
592  // Check if the measurement is in the future where we don't have imu
593  // measurements yet.
594  if (measurement->time > stateBuffer_.getLast()->time) {
595  queueFutureMeasurements_.push(measurement);
596  return;
597 
598  }
599  // Check if there is still a state in the buffer for this message (too old).
600  if (measurement->time < stateBuffer_.getFirst()->time) {
602  "You tried to give me a measurement which is too far in the past. Are "
603  "you sure your clocks are synced and delays compensated correctly? "
604  "[measurement: "<<timehuman(measurement->time)<<" (s) first state in "
605  "buffer: "<<timehuman(stateBuffer_.getFirst()->time)<<" (s)]");
606  return; // Reject measurements too far in the past.
607  }
608 
609  // Add this measurement to the buffer and get an iterator to it.
610  typename measurementBufferT::iterator_T it_meas = MeasurementBuffer_.insert(
611  measurement);
612  // Get an iterator the the end of the measurement buffer.
613  typename measurementBufferT::iterator_T it_meas_end = MeasurementBuffer_
614  .getIteratorEnd();
615 
616  // No propagation if no update is applied.
617  typename StateBuffer_T::iterator_T it_curr = stateBuffer_.getIteratorEnd();
618 
619  bool appliedOne = false;
620 
621  isfuzzyState_ = false;
622 
623  // Now go through all the measurements and apply them one by one.
624  for (; it_meas != it_meas_end; ++it_meas) {
625 
626  if (it_meas->second->time <= 0) // Valid?
627  continue;
628  msf_timing::DebugTimer timer_meas_get_state("Get state for measurement");
629  shared_ptr<EKFState_T> state = getClosestState(it_meas->second->time); // Propagates covariance to state.
630  timer_meas_get_state.Stop();
631  if (state->time <= 0) {
633  1, __FUNCTION__<< " getClosestState returned an invalid state");
634  continue;
635  }
636 
637  msf_timing::DebugTimer timer_meas_apply("Apply measurement");
638  // Calls back core::applyCorrection(), which sets time_P_propagated to meas
639  // time.
640  it_meas->second->apply(state, *this);
641  timer_meas_apply.Stop();
642  // Make sure to propagate to next measurement or up to now if no more
643  // measurements. Propagate from current state.
644  it_curr = stateBuffer_.getIteratorAtValue(state);
645 
646  typename StateBuffer_T::iterator_T it_end;
647  typename measurementBufferT::iterator_T it_nextmeas = it_meas;
648  ++it_nextmeas; // The next measurement in the list.
649  // That was the last measurement, so propagate state to now.
650  if (it_nextmeas == it_meas_end) {
651  it_end = stateBuffer_.getIteratorEnd();
652  } else {
653  it_end = stateBuffer_.getIteratorClosestAfter(it_nextmeas->second->time);
654  if (it_end != stateBuffer_.getIteratorEnd()) {
655  // Propagate to state closest after the measurement so we can interpolate.
656  ++it_end;
657  }
658  }
659 
660  typename StateBuffer_T::iterator_T it_next = it_curr;
661  ++it_next;
662 
663  msf_timing::DebugTimer timer_prop_state_after_meas(
664  "Repropagate state to now");
665  for (; it_curr != it_end && it_next != it_end && it_curr->second->time != -1
666  // Propagate to selected state.
667  && it_next->second->time != -1; ++it_curr, ++it_next) {
668  if (it_curr->second == it_next->second) {
669  MSF_ERROR_STREAM(__FUNCTION__<< " propagation : it_curr points to same "
670  "state as it_next. This must not happen.");
671  continue;
672  }
673  // Break loop if EKF reset in the meantime.
674  if (!initialized_ || !predictionMade_)
675  return;
676  propagateState(it_curr->second, it_next->second);
677  }
678  timer_prop_state_after_meas.Stop();
679  appliedOne = true;
680  }
681 
682  if (!appliedOne) {
683  MSF_ERROR_STREAM("No measurement was applied, this should not happen.");
684  return;
685  }
686 
687  // Now publish the best current estimate.
688  shared_ptr<EKFState_T>& latestState = stateBuffer_.getLast();
689 
690  propPToState(latestState); // Get the latest covariance.
691 
692  usercalc_.publishStateAfterUpdate(latestState);
693 }
694 
695 template<typename EKFState_T>
696 shared_ptr<msf_core::MSF_MeasurementBase<EKFState_T> > MSF_Core<EKFState_T>::getPreviousMeasurement(
697  double time, int sensorID) {
698  typename measurementBufferT::iterator_T it = MeasurementBuffer_
699  .getIteratorAtValue(time);
700  if (it->second->time != time) {
701  MSF_WARN_STREAM("getPreviousMeasurement: Error invalid iterator at value");
702  return MeasurementBuffer_.getInvalid();
703  }
704  --it;
705  typename measurementBufferT::iterator_T itbeforebegin = MeasurementBuffer_
706  .getIteratorBeforeBegin();
707  while (it != itbeforebegin
708  && (it->second->time != time && it->second->sensorID_ != sensorID)) {
709  --it;
710  }
711  if (it == itbeforebegin) {
712  MSF_WARN_STREAM("getPreviousMeasurement: Error hit before begin");
713  return MeasurementBuffer_.getInvalid();
714  }
715  return it->second;
716 }
717 
718 template<typename EKFState_T>
719 shared_ptr<EKFState_T> MSF_Core<EKFState_T>::getStateAtTime(double tstamp) {
720  return stateBuffer_.getValueAt(tstamp);
721 }
722 
723 template<typename EKFState_T>
724 shared_ptr<EKFState_T> MSF_Core<EKFState_T>::getClosestState(double tstamp) {
725 
726  double timenow = tstamp; // Delay compensated by sensor handler.
727 
728  typename StateBuffer_T::iterator_T it = stateBuffer_.getIteratorClosest(
729  timenow);
730 
731  shared_ptr<EKFState_T> closestState = it->second;
732  // Check if the state really is close to the requested time.
733  // With the new buffer this might not be given.
734  if (closestState->time == -1 || fabs(closestState->time - timenow) > 0.1) {
736  __FUNCTION__<< " Requested closest state to "<<timehuman(timenow)<<" but "
737  "there was no suitable state in the map");
738  // Not enough predictions made yet to apply measurement (too far in past).
739  return stateBuffer_.getInvalid();
740  }
741 
742  // Do state interpolation if state is too far away from the measurement.
743  double tdiff = fabs(closestState->time - timenow); // Timediff to closest state.
744  // If time diff too large, insert new state and do state interpolation.
745  if (tdiff > 0.001) {
746  shared_ptr<EKFState_T> lastState = stateBuffer_.getClosestBefore(timenow);
747  shared_ptr<EKFState_T> nextState = stateBuffer_.getClosestAfter(timenow);
748 
749  bool statevalid = lastState->time != -1 && nextState->time != -1;
750  bool statenotnan = lastState->checkStateForNumeric()
751  && nextState->checkStateForNumeric();
752  bool statesnotsame = lastState->time != nextState->time;
753 
754  // If one of the states is invalid, we don't do interpolation, but just
755  // take closest.
756  if (statevalid && statenotnan && statesnotsame) {
757 
758  // Prepare a new state.
759  shared_ptr<EKFState_T> currentState(new EKFState_T);
760  currentState->time = timenow; // Set state time to measurement time.
761  // Linearly interpolate imu readings.
762  currentState->a_m = lastState->a_m
763  + (nextState->a_m - lastState->a_m)
764  / (nextState->time - lastState->time)
765  * (timenow - lastState->time);
766  currentState->w_m = lastState->w_m
767  + (nextState->w_m - lastState->w_m)
768  / (nextState->time - lastState->time)
769  * (timenow - lastState->time);
770 
771  // Propagate with respective dt.
772  propagateState(lastState, currentState);
773 
774  stateBuffer_.insert(currentState);
775 
776  // Make sure we propagate P correctly to the new state.
777  if (time_P_propagated > lastState->time) {
778  time_P_propagated = lastState->time;
779  }
780 
781  closestState = currentState;
782  }
783  }
784  // Catch up with covariance propagation if necessary.
785  propPToState(closestState);
786 
787  if (!closestState->checkStateForNumeric()) {
789  __FUNCTION__<< " State interpolation: interpolated state is invalid (nan)");
790  return stateBuffer_.getInvalid(); // Early abort.
791  }
792 
793  static int janitorRun = 0;
794  if (janitorRun++ > 100) {
795  // Remove very old states and measurements from the buffers.
796  CleanUpBuffers();
797  janitorRun = 0;
798  }
799  return closestState;
800 }
801 
802 template<typename EKFState_T>
803 void MSF_Core<EKFState_T>::propPToState(shared_ptr<EKFState_T>& state) {
804  // Propagate cov matrix until the current states time.
805  typename StateBuffer_T::iterator_T it = stateBuffer_.getIteratorAtValue(
806  time_P_propagated, false);
807  typename StateBuffer_T::iterator_T itMinus = it;
808  ++it;
809  // Until we reached the current state or the end of the state list.
810  for (; it != stateBuffer_.getIteratorEnd() && it->second->time <= state->time;
811  ++it, ++itMinus) {
812  predictProcessCovariance(itMinus->second, it->second);
813  }
814 }
815 
816 template<typename EKFState_T>
817 bool MSF_Core<EKFState_T>::applyCorrection(shared_ptr<EKFState_T>& delaystate,
818  ErrorState & correction,
819  double fuzzythres) {
820 
821  if (!initialized_ || !predictionMade_)
822  return false;
823 
824  // Give the user the possibility to fix some states.
825  usercalc_.augmentCorrectionVector(correction);
826 
827  // Now augment core states.
828  if (usercalc_.getParam_fixed_bias()) {
829  typedef typename msf_tmp::getEnumStateType<StateSequence_T,
830  StateDefinition_T::b_a>::value b_a_type;
831  typedef typename msf_tmp::getEnumStateType<StateSequence_T,
832  StateDefinition_T::b_w>::value b_w_type;
833 
834  enum {
835  indexOfState_b_a = msf_tmp::getStartIndex<StateSequence_T, b_a_type,
836  msf_tmp::CorrectionStateLengthForType>::value,
837  indexOfState_b_w = msf_tmp::getStartIndex<StateSequence_T, b_w_type,
838  msf_tmp::CorrectionStateLengthForType>::value
839  };
840 
841  static_assert(
842  static_cast<int>(indexOfState_b_w)==9,
843  "The index of the state b_w in the correction vector differs from the "
844  "expected value");
845  static_assert(
846  static_cast<int>(indexOfState_b_a)==12,
847  "The index of the state b_a in the correction vector differs from the "
848  "expected value");
849 
850  for (int i = 0;
851  i < msf_tmp::StripConstReference<b_a_type>::result_t::sizeInCorrection_;
852  ++i) {
853  correction(indexOfState_b_a + i) = 0; // Acc bias x,y,z.
854  }
855  for (int i = 0;
856  i < msf_tmp::StripConstReference<b_w_type>::result_t::sizeInCorrection_;
857  ++i) {
858  correction(indexOfState_b_w + i) = 0; // Gyro bias x,y,z.
859  }
860  }
861 
862  // State update:
863  // TODO(slynen) What to do with attitude? Augment measurement noise?
864  // Store old values in case of fuzzy tracking.
865  EKFState_T buffstate = *delaystate;
866 
867  // Call correction function for every state.
868  delaystate->correct(correction);
869 
870  // Allow the user to sanity check the new state.
871  usercalc_.sanityCheckCorrection(*delaystate, buffstate, correction);
872 
873  // TODO(slynen): Allow multiple fuzzy tracking states at the same time.
874  isfuzzyState_ |= fuzzyTracker_.check(delaystate, buffstate, fuzzythres);
875 
876  // No publishing and propagation here, because this might not be the last
877  // update we have to apply.
878  checkForNumeric(correction, "update");
879 
880  // Set time latest propagated, we need to repropagate at least from here.
881  time_P_propagated = delaystate->time;
882 
883  return 1;
884 }
885 } // namespace msf_core