26 #include <msf_timing/Timer.h>
36 template<
typename EKFState_T>
38 : usercalc_(usercalc) {
51 template<
typename EKFState_T>
55 template<
typename EKFState_T>
57 Eigen::Matrix<
double, EKFState_T::nErrorStatesAtCompileTime,
58 EKFState_T::nErrorStatesAtCompileTime>& P) {
68 Eigen::Matrix<double, coreErrorStates, coreErrorStates> P_core;
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;
86 P_core = 0.5 * (P_core + P_core.transpose());
87 P.template block<coreErrorStates, coreErrorStates>(0, 0) = P_core;
90 template<
typename EKFState_T>
95 template<
typename EKFState_T>
97 const msf_core::Vector3& linear_acceleration,
98 const msf_core::Vector3& angular_velocity,
const double& msg_stamp,
104 msf_timing::DebugTimer timer_PropgetClosestState(
"PropgetClosestState");
105 if (it_last_IMU == stateBuffer_.getIteratorEnd()) {
106 it_last_IMU = stateBuffer_.getIteratorClosestBefore(msg_stamp);
109 shared_ptr<EKFState_T> lastState = it_last_IMU->second;
110 timer_PropgetClosestState.Stop();
112 msf_timing::DebugTimer timer_PropPrepare(
"PropPrepare");
113 if (lastState->time == -1) {
115 2, __FUNCTION__<<
"ImuCallback: closest state is invalid\n");
119 shared_ptr<EKFState_T> currentState(
new EKFState_T);
120 currentState->time = msg_stamp;
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, "
135 currentState->a_m = linear_acceleration;
136 currentState->w_m = angular_velocity;
139 static Eigen::Matrix<double, 3, 1> last_am = Eigen::Matrix<double, 3, 1>(0, 0,
141 if (currentState->a_m.norm() > 50)
142 currentState->a_m = last_am;
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");
151 last_am = lastState->a_m;
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");
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;
169 if (lastState->time == -1) {
171 "Wanted to propagate state, but no valid prior state could be found in "
175 timer_PropPrepare.Stop();
177 msf_timing::DebugTimer timer_PropState(
"PropState");
179 propagateState(lastState, currentState);
180 timer_PropState.Stop();
181 msf_timing::DebugTimer timer_PropCov(
"PropCov");
183 timer_PropCov.Stop();
185 usercalc_.publishStateAfterPropagation(currentState);
188 if (stateBuffer_.size() > 3)
189 predictionMade_ =
true;
191 msf_timing::DebugTimer timer_PropInsertState(
"PropInsertState");
192 it_last_IMU = stateBuffer_.insert(currentState);
193 timer_PropInsertState.Stop();
195 if (predictionMade_) {
197 handlePendingMeasurements();
203 template<
typename EKFState_T>
205 const msf_core::Vector3& linear_acceleration,
206 const msf_core::Vector3& angular_velocity,
const msf_core::Vector3&
p,
208 bool is_already_propagated,
const double& msg_stamp,
size_t msg_seq) {
223 shared_ptr<EKFState_T> lastState = stateBuffer_.getLast();
224 if (lastState->time == -1) {
230 shared_ptr<EKFState_T> currentState(
new EKFState_T);
231 currentState->time = msg_stamp;
234 currentState->a_m = linear_acceleration;
235 currentState->w_m = angular_velocity;
238 static Eigen::Matrix<double, 3, 1> last_am = Eigen::Matrix<double, 3, 1>(0, 0,
240 if (currentState->a_m.norm() > 50)
241 currentState->a_m = last_am;
243 last_am = currentState->a_m;
245 if (!predictionMade_) {
246 if (fabs(currentState->time - lastState->time) > 5) {
248 lastState->time, currentState->time);
257 currentState->template get<StateDefinition_T::p>(),
258 "before prediction p");
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;
267 boost::fusion::for_each(
268 currentState->statevars,
271 }
else if (!is_already_propagated || !isnumeric) {
273 propagateState(lastState, currentState);
279 currentState->template get<StateDefinition_T::p>(),
"prediction p");
283 if (!predictionMade_) {
286 currentState->P = stateBuffer_.getLast()->P;
287 time_P_propagated = currentState->time;
289 stateBuffer_.clear();
290 MeasurementBuffer_.clear();
291 while (!queueFutureMeasurements_.empty()) {
292 queueFutureMeasurements_.pop();
295 predictionMade_ =
true;
297 stateBuffer_.insert(currentState);
299 handlePendingMeasurements();
302 template<
typename EKFState_T>
304 if (queueFutureMeasurements_.empty())
306 shared_ptr<MSF_MeasurementBase<EKFState_T> > meas = queueFutureMeasurements_
308 queueFutureMeasurements_.pop();
309 addMeasurement(meas);
312 template<
typename EKFState_T>
315 stateBuffer_.clearOlderThan(timeold);
316 MeasurementBuffer_.clearOlderThan(timeold);
319 template<
typename EKFState_T>
321 shared_ptr<EKFState_T>& state_new) {
323 double dt = state_new->time - state_old->time;
329 boost::fusion::for_each(
330 state_new->statevars,
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>();
354 MatExp.setIdentity();
355 OmegaMean *= 0.5 * dt;
356 for (
int i = 1; i < 5; i++) {
358 MatExp = MatExp + OmegaMean / div;
359 OmegaMean *= OmegaMean;
363 const Matrix4 quat_int = MatExp
364 + 1.0 / 48.0 * (Omega * OmegaOld - OmegaOld * Omega) * dt * dt;
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();
371 dv = (state_new->template get<StateDefinition_T::q>().toRotationMatrix() *
372 ea + state_old->
template get<StateDefinition_T::q>().toRotationMatrix() *
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);
382 template<
typename EKFState_T>
387 .getIteratorAtValue(time_P_propagated,
false);
389 stateIteratorPLastPropagated;
391 ++stateIteratorPLastPropagatedNext;
393 if (stateIteratorPLastPropagatedNext != stateBuffer_.getIteratorEnd()) {
395 predictProcessCovariance(stateIteratorPLastPropagated->second,
396 stateIteratorPLastPropagatedNext->second);
399 stateIteratorPLastPropagatedNext->second
400 ->template get<StateDefinition_T::p>(),
403 "prop state from:\t"<< stateIteratorPLastPropagated->second->toEigenVector());
405 "prop state to:\t"<< stateIteratorPLastPropagatedNext->second->toEigenVector());
407 predictionMade_ = initialized_ =
false;
412 template<
typename EKFState_T>
414 const shared_ptr<EKFState_T>& state_old,
415 const shared_ptr<EKFState_T>& 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;
430 template<
typename EKFState_T>
432 shared_ptr<EKFState_T>& state_old, shared_ptr<EKFState_T>& state_new) {
434 double dt = state_new->time - state_old->time;
438 1,
"Requested cov prop between two states that where "<<dt<<
" "
439 "seconds apart. Rejecting");
444 const Vector3 nav = Vector3::Constant(usercalc_.getParam_noise_acc());
445 const Vector3 nbav = Vector3::Constant(usercalc_.getParam_noise_accbias());
447 const Vector3 nwv = Vector3::Constant(usercalc_.getParam_noise_gyr());
448 const Vector3 nbwv = Vector3::Constant(usercalc_.getParam_noise_gyrbias());
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>();
456 const Matrix3 a_sk =
skew(ea);
457 const Matrix3 w_sk =
skew(ew);
458 const Matrix3 eye3 = Eigen::Matrix<double, 3, 3>::Identity();
460 const Matrix3 C_eq = state_new->template get<StateDefinition_T::q>().toRotationMatrix();
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;
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;
481 typename EKFState_T::F_type& Fd = state_old->Fd;
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;
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;
505 Fd.template block<3, 3>(idxstartcorr_q, idxstartcorr_q) = E;
506 Fd.template block<3, 3>(idxstartcorr_q, idxstartcorr_b_w) = F;
508 typename EKFState_T::Q_type& Qd = state_old->Qd;
510 calc_QCore<StateSequence_T, StateDefinition_T>(
511 dt, state_new->template get<StateDefinition_T::q>(), ew, ea, nav, nbav,
517 usercalc_.calculateQAuxiliaryStates(*state_new, dt);
520 boost::fusion::for_each(
521 state_new->statevars,
526 state_new->P = Fd * state_old->P * Fd.transpose() + Qd;
529 time_P_propagated = state_new->time;
533 template<
typename EKFState_T>
537 initialized_ =
false;
538 predictionMade_ =
false;
542 MeasurementBuffer_.clear();
543 stateBuffer_.clear();
544 fuzzyTracker_.reset();
546 while (!queueFutureMeasurements_.empty())
547 queueFutureMeasurements_.pop();
550 shared_ptr<EKFState_T> state(
new EKFState_T);
560 measurement->apply(state, *
this);
565 assert(state->time != 0);
567 it_last_IMU = stateBuffer_.insert(state);
570 time_P_propagated = state->time;
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);
578 MSF_INFO_STREAM(
"Core init with state: " << std::endl << state->print());
581 msf_timing::Timing::Print(std::cout);
584 template<
typename EKFState_T>
589 if (!initialized_ || !predictionMade_)
594 if (measurement->time > stateBuffer_.getLast()->time) {
595 queueFutureMeasurements_.push(measurement);
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)]");
619 bool appliedOne =
false;
621 isfuzzyState_ =
false;
624 for (; it_meas != it_meas_end; ++it_meas) {
626 if (it_meas->second->time <= 0)
628 msf_timing::DebugTimer timer_meas_get_state(
"Get state for measurement");
629 shared_ptr<EKFState_T> state = getClosestState(it_meas->second->time);
630 timer_meas_get_state.Stop();
631 if (state->time <= 0) {
633 1, __FUNCTION__<<
" getClosestState returned an invalid state");
637 msf_timing::DebugTimer timer_meas_apply(
"Apply measurement");
640 it_meas->second->apply(state, *
this);
641 timer_meas_apply.Stop();
644 it_curr = stateBuffer_.getIteratorAtValue(state);
650 if (it_nextmeas == it_meas_end) {
651 it_end = stateBuffer_.getIteratorEnd();
653 it_end = stateBuffer_.getIteratorClosestAfter(it_nextmeas->second->time);
654 if (it_end != stateBuffer_.getIteratorEnd()) {
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
667 && it_next->second->time != -1; ++it_curr, ++it_next) {
668 if (it_curr->second == it_next->second) {
670 "state as it_next. This must not happen.");
674 if (!initialized_ || !predictionMade_)
676 propagateState(it_curr->second, it_next->second);
678 timer_prop_state_after_meas.Stop();
688 shared_ptr<EKFState_T>& latestState = stateBuffer_.getLast();
690 propPToState(latestState);
692 usercalc_.publishStateAfterUpdate(latestState);
695 template<
typename EKFState_T>
697 double time,
int sensorID) {
699 .getIteratorAtValue(time);
700 if (it->second->time != time) {
701 MSF_WARN_STREAM(
"getPreviousMeasurement: Error invalid iterator at value");
702 return MeasurementBuffer_.getInvalid();
706 .getIteratorBeforeBegin();
707 while (it != itbeforebegin
708 && (it->second->time != time && it->second->sensorID_ != sensorID)) {
711 if (it == itbeforebegin) {
713 return MeasurementBuffer_.getInvalid();
718 template<
typename EKFState_T>
720 return stateBuffer_.getValueAt(tstamp);
723 template<
typename EKFState_T>
726 double timenow = tstamp;
731 shared_ptr<EKFState_T> closestState = it->second;
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");
739 return stateBuffer_.getInvalid();
743 double tdiff = fabs(closestState->time - timenow);
746 shared_ptr<EKFState_T> lastState = stateBuffer_.getClosestBefore(timenow);
747 shared_ptr<EKFState_T> nextState = stateBuffer_.getClosestAfter(timenow);
749 bool statevalid = lastState->time != -1 && nextState->time != -1;
750 bool statenotnan = lastState->checkStateForNumeric()
751 && nextState->checkStateForNumeric();
752 bool statesnotsame = lastState->time != nextState->time;
756 if (statevalid && statenotnan && statesnotsame) {
759 shared_ptr<EKFState_T> currentState(
new EKFState_T);
760 currentState->time = timenow;
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);
772 propagateState(lastState, currentState);
774 stateBuffer_.insert(currentState);
777 if (time_P_propagated > lastState->time) {
778 time_P_propagated = lastState->time;
781 closestState = currentState;
785 propPToState(closestState);
787 if (!closestState->checkStateForNumeric()) {
789 __FUNCTION__<<
" State interpolation: interpolated state is invalid (nan)");
790 return stateBuffer_.getInvalid();
793 static int janitorRun = 0;
794 if (janitorRun++ > 100) {
802 template<
typename EKFState_T>
806 time_P_propagated,
false);
810 for (; it != stateBuffer_.getIteratorEnd() && it->second->time <= state->time;
812 predictProcessCovariance(itMinus->second, it->second);
816 template<
typename EKFState_T>
821 if (!initialized_ || !predictionMade_)
825 usercalc_.augmentCorrectionVector(correction);
828 if (usercalc_.getParam_fixed_bias()) {
831 typedef typename msf_tmp::getEnumStateType<StateSequence_T,
836 msf_tmp::CorrectionStateLengthForType>::value,
838 msf_tmp::CorrectionStateLengthForType>::value
842 static_cast<int>(indexOfState_b_w)==9,
843 "The index of the state b_w in the correction vector differs from the "
846 static_cast<int>(indexOfState_b_a)==12,
847 "The index of the state b_a in the correction vector differs from the "
851 i < msf_tmp::StripConstReference<b_a_type>::result_t::sizeInCorrection_;
853 correction(indexOfState_b_a + i) = 0;
856 i < msf_tmp::StripConstReference<b_w_type>::result_t::sizeInCorrection_;
858 correction(indexOfState_b_w + i) = 0;
865 EKFState_T buffstate = *delaystate;
868 delaystate->correct(correction);
871 usercalc_.sanityCheckCorrection(*delaystate, buffstate, correction);
874 isfuzzyState_ |= fuzzyTracker_.check(delaystate, buffstate, fuzzythres);
881 time_P_propagated = delaystate->time;