Go to the documentation of this file.
44 template <
class VALUE>
51 typedef std::shared_ptr<ExtendedKalmanFilter<VALUE> >
shared_ptr;
72 void print(
const std::string&
s =
"")
const {
73 std::cout <<
s <<
"\n";
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< Gaussian > shared_ptr
void print(const std::string &s="") const
print
T update(const NoiseModelFactor &measurementFactor)
JacobianFactor::shared_ptr priorFactor_
GTSAM_CONCEPT_ASSERT(IsTestable< VALUE >)
static T solve_(const GaussianFactorGraph &linearFactorGraph, const Values &linearizationPoints, Key x, JacobianFactor::shared_ptr *newPrior)
A small structure to hold a non zero as a triplet (i,j,value).
T predict(const NoiseModelFactor &motionFactor)
Non-linear factor base classes.
Class to perform generic Kalman Filtering using nonlinear factor graphs.
std::shared_ptr< ExtendedKalmanFilter< VALUE > > shared_ptr
Factor Graph consisting of non-linear factors.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
std::uint64_t Key
Integer nonlinear key type.
const JacobianFactor::shared_ptr Density() const
Return current predictive (if called after predict)/posterior (if called after update)
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:32