47 return std::make_shared<GaussianDensity>(*posterior);
61 return solve(factorGraph);
71 return solve(factorGraph);
80 return solve(factorGraph);
85 cout <<
"KalmanFilter " << s <<
", dim = " << n_ << endl;
96 std::make_shared<JacobianFactor>(k, -F, k + 1, I_, B * u, model));
105 assert(F.rows() ==
n);
106 assert(B.rows() ==
n);
107 assert(B.cols() == u.size());
108 assert(Q.rows() ==
n);
109 assert(Q.cols() ==
n);
117 Matrix G12 = -Ft *
M, G11 = -G12 *
F, G22 =
M;
119 double f =
dot(b, g2);
122 std::make_shared<HessianFactor>(k, k + 1, G11, G12, g1, G22, g2, f));
131 return fuse(p, std::make_shared<JacobianFactor>(k, A0, k + 1, A1, b, model));
141 return fuse(p, std::make_shared<JacobianFactor>(k, H, z, model));
151 double f =
dot(z, M * z);
152 return fuse(p, std::make_shared<HessianFactor>(k, G, g, f));
def step(data, isam, result, truth, currPoseIndex)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Matrix< RealScalar, Dynamic, Dynamic > M
Concept check for values that can be used in unit tests.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
JacobiRotation< float > G
noiseModel::Diagonal::shared_ptr model
GaussianDensity::shared_ptr State
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
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
static enum @1107 ordering
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
Scalar EIGEN_BLAS_FUNC() dot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Contains the HessianFactor class, a general quadratic factor.
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
internal::DoglegState State
noiseModel::Diagonal::shared_ptr SharedDiagonal
Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF...
The quaternion class used to represent 3D orientations and rotations.
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
A Gaussian factor using the canonical parameters (information form)
Chordal Bayes Net, the result of eliminating a factor graph.
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
Pose3 g2(g1.expmap(h *V1_g1))
std::uint64_t Key
Integer nonlinear key type.