Go to the documentation of this file.
32 const Values& linearizationPoint,
Key lastKey,
38 const Ordering lastKeyAsOrdering{lastKey};
44 const T& current = linearizationPoint.
at<
T>(lastKey);
51 assert(marginal->nrFrontals() == 1);
52 assert(marginal->nrParents() == 0);
53 *newPrior = std::make_shared<JacobianFactor>(
54 marginal->keys().front(),
55 marginal->getA(marginal->begin()),
56 marginal->getb() - marginal->getA(marginal->begin()) *
result[lastKey],
57 marginal->get_model());
63 template <
class VALUE>
81 const auto keys = motionFactor.
keys();
87 linearFactorGraph.
push_back(priorFactor_);
97 x_ = solve_(linearFactorGraph, linearizationPoint,
keys[1], &priorFactor_);
103 template<
class VALUE>
106 const auto keys = measurementFactor.
keys();
112 linearFactorGraph.
push_back(priorFactor_);
115 Values linearizationPoint;
121 x_ = solve_(linearFactorGraph, linearizationPoint,
keys[0], &priorFactor_);
Linear Factor Graph where all factors are Gaussians.
ExtendedKalmanFilter(Key key_initial, T x_initial, noiseModel::Gaussian::shared_ptr P_initial)
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 x
std::shared_ptr< BayesNetType > marginalMultifrontalBayesNet(const Ordering &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Chordal Bayes Net, the result of eliminating a factor graph.
std::shared_ptr< Gaussian > shared_ptr
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
const ValueType at(Key j) const
T update(const NoiseModelFactor &measurementFactor)
JacobianFactor::shared_ptr priorFactor_
static shared_ptr Create(size_t dim)
static T solve_(const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior)
T predict(const NoiseModelFactor &motionFactor)
Class to perform generic Kalman Filtering using nonlinear factor graphs.
Non-linear factor base classes.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
const KeyVector & keys() const
Access the factor's involved variable keys.
void insert(Key j, const Value &val)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
std::shared_ptr< This > shared_ptr
shared_ptr to this class
std::uint64_t Key
Integer nonlinear key type.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:17