36template <
int CovDim,
int States>
37std::tuple<Vectord<CovDim>, Matrixd<CovDim, CovDim>>
55 for (
int i = 0; i < States * 2; i++) {
56 Sbar.template block<CovDim, 1>(0, i) =
58 residualFunc(sigmas.template block<CovDim, 1>(0, 1 + i), x);
60 Sbar.template block<CovDim, CovDim>(0, States * 2) = squareRootR;
66 .template block<CovDim, CovDim>(0, 0)
67 .template triangularView<Eigen::Upper>();
70 S, residualFunc(sigmas.template block<CovDim, 1>(0, 0), x), Wc[0]);
72 return std::make_tuple(x,
S);
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition: math.h:483
Definition: AprilTagPoseEstimator.h:15
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:38
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
#define S(label, offset, message)
Definition: Errors.h:119