ukf.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.
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
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef ROBOT_LOCALIZATION_UKF_H
34 #define ROBOT_LOCALIZATION_UKF_H
35 
37 
38 #include <fstream>
39 #include <vector>
40 #include <set>
41 #include <queue>
42 
43 namespace RobotLocalization
44 {
45 
60 class Ukf: public FilterBase
61 {
62  public:
69  explicit Ukf(std::vector<double> args);
70 
73  ~Ukf();
74 
79  void correct(const Measurement &measurement);
80 
89  void predict(const double referenceTime, const double delta);
90 
91  protected:
96  std::vector<Eigen::VectorXd> sigmaPoints_;
97 
100  Eigen::MatrixXd weightedCovarSqrt_;
101 
105  std::vector<double> stateWeights_;
106 
110  std::vector<double> covarWeights_;
111 
114  double lambda_;
115 
120 };
121 
122 } // namespace RobotLocalization
123 
124 #endif // ROBOT_LOCALIZATION_UKF_H
std::vector< Eigen::VectorXd > sigmaPoints_
The UKF sigma points.
Definition: ukf.h:96
Eigen::MatrixXd weightedCovarSqrt_
This matrix is used to generate the sigmaPoints_.
Definition: ukf.h:100
Unscented Kalman filter class.
Definition: ukf.h:60
void correct(const Measurement &measurement)
Carries out the correct step in the predict/update cycle.
Definition: ukf.cpp:85
Structure used for storing and comparing measurements (for priority queues)
Definition: filter_base.h:61
std::vector< double > covarWeights_
The weights associated with each sigma point when calculating a predicted estimateErrorCovariance_.
Definition: ukf.h:110
~Ukf()
Destructor for the Ukf class.
Definition: ukf.cpp:81
void predict(const double referenceTime, const double delta)
Carries out the predict step in the predict/update cycle.
Definition: ukf.cpp:284
Ukf(std::vector< double > args)
Constructor for the Ukf class.
Definition: ukf.cpp:51
bool uncorrected_
Used to determine if we need to re-compute the sigma points when carrying out multiple corrections...
Definition: ukf.h:119
std::vector< double > stateWeights_
The weights associated with each sigma point when generating a new state.
Definition: ukf.h:105
double lambda_
Used in weight generation for the sigma points.
Definition: ukf.h:114


robot_localization
Author(s): Tom Moore
autogenerated on Wed Feb 3 2021 03:34:02