Go to the documentation of this file.
65 return std::make_shared<GaussianDensity>(*posterior);
78 return solve(factorGraph);
88 return solve(factorGraph);
104 return solve(factorGraph);
109 std::cout <<
"KalmanFilter " <<
s <<
", dim = " <<
n_ << std::endl;
121 std::make_shared<JacobianFactor>(k, -
F, k + 1,
I_,
B * u,
model));
130 assert(
F.cols() ==
n);
131 assert(
F.rows() ==
n);
132 assert(
B.rows() ==
n);
133 assert(
B.cols() == u.size());
134 assert(
Q.rows() ==
n);
135 assert(
Q.cols() ==
n);
155 return fuse(
p, std::make_shared<JacobianFactor>(k,
A0, k + 1,
A1,
b,
model));
166 return fuse(
p, std::make_shared<JacobianFactor>(k,
H,
z,
model));
181 return fuse(
p, std::make_shared<JacobianFactor>(k,
A,
b));
static Key step(const State &p)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Namespace containing all symbols from the Eigen library.
const size_t n_
Dimensionality of the state.
Concept check for values that can be used in unit tests.
const Matrix I_
Identity matrix of size .
GaussianDensity::shared_ptr State
The Kalman filter state, represented as a shared pointer to a GaussianDensity.
Chordal Bayes Net, the result of eliminating a factor graph.
const EIGEN_DEVICE_FUNC Product< MatrixDerived, PermutationDerived, AliasFreeProduct > operator*(const MatrixBase< MatrixDerived > &matrix, const PermutationBase< PermutationDerived > &permutation)
State predict(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const SharedDiagonal &modelQ) const
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
State fuse(const State &p, GaussianFactor::shared_ptr newFactor) const
State predict2(const State &p, const Matrix &A0, const Matrix &A1, const Vector &b, const SharedDiagonal &model=nullptr) const
const HybridBayesNet bayesNet
Traits::MatrixL matrixL() const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
noiseModel::Diagonal::shared_ptr SharedDiagonal
void print(const std::string &s="") const
noiseModel::Diagonal::shared_ptr model
static enum @1096 ordering
State predictQ(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const Matrix &Q) const
Simple linear Kalman filter implemented using factor graphs, i.e., performs Cholesky or QR-based SRIF...
State solve(const GaussianFactorGraph &factorGraph) const
The quaternion class used to represent 3D orientations and rotations.
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
ptrdiff_t DenseIndex
The index type for Eigen objects.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
State updateQ(const State &p, const Matrix &H, const Vector &z, const Matrix &R) const
State update(const State &p, const Matrix &H, const Vector &z, const SharedDiagonal &model) const
const GaussianFactorGraph::Eliminate function_
Elimination algorithm used.
std::uint64_t Key
Integer nonlinear key type.
State init(const Vector &x0, const SharedDiagonal &P0) const
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:51