Public Types | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N > Class Template Reference

#include <unscented_kalman_filter.h>

Public Types

using StateCovarianceType = Eigen::Matrix< FloatType, N, N >
 
using StateType = Eigen::Matrix< FloatType, N, 1 >
 

Public Member Functions

const GaussianDistribution< FloatType, N > & GetBelief () const
 
template<int K>
void Observe (std::function< Eigen::Matrix< FloatType, K, 1 >(const StateType &)> h, const GaussianDistribution< FloatType, K > &delta)
 
void Predict (std::function< StateType(const StateType &)> g, const GaussianDistribution< FloatType, N > &epsilon)
 
 UnscentedKalmanFilter (const GaussianDistribution< FloatType, N > &initial_belief, std::function< StateType(const StateType &state, const StateType &delta)> add_delta=[](const StateType &state, const StateType &delta){return state+delta;}, std::function< StateType(const StateType &origin, const StateType &target)> compute_delta=[](const StateType &origin, const StateType &target){return target-origin;})
 

Private Member Functions

StateType ComputeMean (const std::vector< StateType > &states)
 
StateType ComputeWeightedError (const StateType &mean_estimate, const std::vector< StateType > &states)
 

Private Attributes

const std::function< StateType(const StateType &state, const StateType &delta)> add_delta_
 
GaussianDistribution< FloatType, N > belief_
 
const std::function< StateType(const StateType &origin, const StateType &target)> compute_delta_
 

Static Private Attributes

static constexpr FloatType kAlpha = 1e-3
 
static constexpr FloatType kBeta = 2.
 
static constexpr FloatType kCovWeight0
 
static constexpr FloatType kCovWeightI = kMeanWeightI
 
static constexpr FloatType kKappa = 0.
 
static constexpr FloatType kLambda = sqr(kAlpha) * (N + kKappa) - N
 
static constexpr FloatType kMeanWeight0 = kLambda / (N + kLambda)
 
static constexpr FloatType kMeanWeightI = 1. / (2. * (N + kLambda))
 

Detailed Description

template<typename FloatType, int N>
class cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >

Definition at line 83 of file unscented_kalman_filter.h.

Member Typedef Documentation

template<typename FloatType, int N>
using cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::StateCovarianceType = Eigen::Matrix<FloatType, N, N>

Definition at line 86 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
using cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::StateType = Eigen::Matrix<FloatType, N, 1>

Definition at line 85 of file unscented_kalman_filter.h.

Constructor & Destructor Documentation

template<typename FloatType, int N>
cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::UnscentedKalmanFilter ( const GaussianDistribution< FloatType, N > &  initial_belief,
std::function< StateType(const StateType &state, const StateType &delta)>  add_delta = [](const StateType& state,                         const StateType& delta) { return state + delta; },
std::function< StateType(const StateType &origin, const StateType &target)>  compute_delta = [](const StateType& origin, const StateType& target) { return target - origin; } 
)
inlineexplicit

Definition at line 88 of file unscented_kalman_filter.h.

Member Function Documentation

template<typename FloatType, int N>
StateType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::ComputeMean ( const std::vector< StateType > &  states)
inlineprivate

Definition at line 225 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
StateType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::ComputeWeightedError ( const StateType mean_estimate,
const std::vector< StateType > &  states 
)
inlineprivate

Definition at line 213 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
const GaussianDistribution<FloatType, N>& cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::GetBelief ( ) const
inline

Definition at line 208 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
template<int K>
void cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::Observe ( std::function< Eigen::Matrix< FloatType, K, 1 >(const StateType &)>  h,
const GaussianDistribution< FloatType, K > &  delta 
)
inline

Definition at line 144 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
void cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::Predict ( std::function< StateType(const StateType &)>  g,
const GaussianDistribution< FloatType, N > &  epsilon 
)
inline

Definition at line 105 of file unscented_kalman_filter.h.

Member Data Documentation

template<typename FloatType, int N>
const std::function<StateType(const StateType& state, const StateType& delta)> cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::add_delta_
private

Definition at line 265 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
GaussianDistribution<FloatType, N> cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::belief_
private

Definition at line 263 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
const std::function<StateType(const StateType& origin, const StateType& target)> cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::compute_delta_
private

Definition at line 268 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kAlpha = 1e-3
staticprivate

Definition at line 253 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kBeta = 2.
staticprivate

Definition at line 255 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kCovWeight0
staticprivate
Initial value:
=
kLambda / (N + kLambda) + (1. - sqr(kAlpha) + kBeta)

Definition at line 258 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kCovWeightI = kMeanWeightI
staticprivate

Definition at line 261 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kKappa = 0.
staticprivate

Definition at line 254 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kLambda = sqr(kAlpha) * (N + kKappa) - N
staticprivate

Definition at line 256 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kMeanWeight0 = kLambda / (N + kLambda)
staticprivate

Definition at line 257 of file unscented_kalman_filter.h.

template<typename FloatType, int N>
constexpr FloatType cartographer::kalman_filter::UnscentedKalmanFilter< FloatType, N >::kMeanWeightI = 1. / (2. * (N + kLambda))
staticprivate

Definition at line 260 of file unscented_kalman_filter.h.


The documentation for this class was generated from the following file:


cartographer
Author(s):
autogenerated on Wed Jun 5 2019 21:58:00