66 for (
int i = 0; i < States * 2; i++) {
67 Sbar.template block<CovDim, 1>(0, i) =
69 residualFunc(sigmas.template block<CovDim, 1>(0, 1 + i), x);
71 Sbar.template block<CovDim, CovDim>(0, States * 2) = squareRootR;
87 .template block<CovDim, CovDim>(0, 0)
88 .template triangularView<Eigen::Upper>()
95 Eigen::internal::llt_inplace<double, Eigen::Lower>::rankUpdate(
96 S, residualFunc(sigmas.template block<CovDim, 1>(0, 0), x), Wc[0]);
98 return std::make_tuple(x,
S);
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform(const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, const Vectord< 2 *States+1 > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFunc, std::function< Vectord< CovDim >(const Vectord< CovDim > &, const Vectord< CovDim > &)> residualFunc, const Matrixd< CovDim, CovDim > &squareRootR)
Computes unscented transform of a set of sigma points and weights.
Definition UnscentedTransform.h:40
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
#define S(label, offset, message)
Definition Errors.h:113