ekf.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
31 
32 #include <boost/pointer_cast.hpp>
33 
34 #ifdef USE_HECTOR_TIMING
35  #include <hector_diagnostics/timing.h>
36 #endif
37 
38 namespace hector_pose_estimation {
39 namespace filter {
40 
41 EKF::EKF(State &state)
42  : Filter(state)
43 {}
44 
46 {}
47 
48 bool EKF::init(PoseEstimation &estimator)
49 {
53  return true;
54 }
55 
56 bool EKF::preparePredict(double dt)
57 {
58  x_diff.setZero();
59  A.setIdentity();
60  Q.setZero();
61  return Filter::preparePredict(dt);
62 }
63 
64 bool EKF::predict(const SystemPtr& system, double dt)
65 {
66  if (!Filter::predict(system, dt)) return false;
67  EKF::Predictor *predictor = boost::dynamic_pointer_cast<EKF::Predictor>(system->predictor());
68  x_diff += predictor->x_diff;
69  A += predictor->A;
70  Q += predictor->Q;
71  return true;
72 }
73 
74 bool EKF::doPredict(double dt) {
75  ROS_DEBUG_NAMED("ekf.prediction", "EKF prediction (dt = %f):", dt);
76 
77  ROS_DEBUG_STREAM_NAMED("ekf.prediction", "A = [" << std::endl << A << "]");
78  ROS_DEBUG_STREAM_NAMED("ekf.prediction", "Q = [" << std::endl << Q << "]");
79 
80 #ifdef USE_HECTOR_TIMING
81  { hector_diagnostics::TimingSection section("predict.ekf.covariance");
82 #endif
83  state().P() = A * state().P() * A.transpose() + Q;
84  state().P().assertSymmetric();
85 
86 #ifdef USE_HECTOR_TIMING
87  }
88  { hector_diagnostics::TimingSection section("predict.ekf.state");
89 #endif
90  state().update(x_diff);
91 
92 #ifdef USE_HECTOR_TIMING
93  }
94 #endif
95 
96  ROS_DEBUG_STREAM_NAMED("ekf.prediction", "x_pred = [" << state().getVector().transpose() << "]");
97  ROS_DEBUG_STREAM_NAMED("ekf.prediction", "P_pred = [" << std::endl << state().getCovariance() << "]");
98 
100  return true;
101 }
102 
103 } // namespace filter
104 } // namespace hector_pose_estimation
#define ROS_DEBUG_STREAM_NAMED(name, args)
SymmetricMatrix Covariance
Definition: state.h:45
State::SystemMatrix A
Definition: ekf.h:152
virtual bool doPredict(double dt)
Definition: ekf.cpp:74
virtual bool preparePredict(double dt)
Definition: filter.cpp:61
virtual bool doPredict(double dt)
Definition: filter.cpp:94
virtual const State & state() const
Definition: filter.h:50
#define ROS_DEBUG_NAMED(name,...)
virtual bool init(PoseEstimation &estimator)
Definition: ekf.cpp:48
virtual bool preparePredict(double dt)
Definition: ekf.cpp:56
virtual IndexType getCovarianceDimension() const
Definition: state.h:77
virtual Covariance & P()
Definition: state.h:93
virtual bool predict(const Systems &systems, double dt)
Definition: filter.cpp:66
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EKF(State &state)
Definition: ekf.cpp:41
virtual IndexType getVectorDimension() const
Definition: state.h:76
virtual bool predict(const SystemPtr &system, double dt)
Definition: ekf.cpp:64
virtual void update(const Vector &vector_update)
Definition: state.cpp:160


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Thu Feb 18 2021 03:29:30