34 class GaussianBayesNet;
35 class GaussianFactorGraph;
162 const std::vector<Vector>& gs,
double f);
166 template<
typename KEYS>
189 return std::make_shared<HessianFactor>(*this); }
192 void print(
const std::string&
s =
"",
285 Matrix augmentedInformation()
const override;
293 Matrix information()
const override;
299 using Base::hessianDiagonal;
302 void hessianDiagonal(
double* d)
const override;
305 std::map<Key,Matrix> hessianBlockDiagonal()
const override;
308 std::pair<Matrix, Vector> jacobian()
const override;
315 Matrix augmentedJacobian()
const override;
339 void gradientAtZero(
double* d)
const override;
351 std::shared_ptr<GaussianConditional> eliminateCholesky(
const Ordering& keys);
358 void Allocate(
const Scatter& scatter);
366 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 368 friend class boost::serialization::access;
369 template<
class ARCHIVE>
370 void serialize(ARCHIVE & ar,
const unsigned int ) {
372 ar & BOOST_SERIALIZATION_NVP(info_);
393 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<HessianFactor> >
411 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<GaussianFactor> >
void print(const Matrix &A, const string &s, ostream &stream)
const gtsam::Symbol key('X', 0)
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
std::string serialize(const T &input)
serializes to a string
SymmetricBlockMatrix & info()
JacobiRotation< float > G
constBlock aboveDiagonalRange(DenseIndex i_startBlock, DenseIndex i_endBlock, DenseIndex j_startBlock, DenseIndex j_endBlock) const
Get a range [i,j) from the matrix. Indices are in block units.
A factor with a quadratic error function - a Gaussian.
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 view
GaussianFactor::shared_ptr clone() const override
GaussianFactor Base
Typedef to base class.
const GaussianFactorGraph factors
Double_ distance(const OrientedPlane3_ &p)
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
KeyVector keys_
The keys involved in this factor.
SymmetricBlockMatrix::constBlock constBlock
A block from the Hessian matrix (const version)
static const KeyFormatter DefaultKeyFormatter
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
const KeyFormatter & formatter
HessianFactor This
Typedef to this class.
DenseIndex rows() const
Row size.
~HessianFactor() override
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< HessianFactor > > EliminateCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Expression of a selfadjoint matrix from a triangular part of a dense matrix.
double constantTerm() const
SymmetricBlockMatrix::constBlock linearTerm() const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
SymmetricBlockMatrix::Block Block
A block from the Hessian matrix.
SymmetricBlockMatrix info_
The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'H[x -1]...
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Maps global variable indices to slot indices.
A thin wrapper around std::vector that uses a custom allocator.
SymmetricBlockMatrix::constBlock linearTerm(const_iterator j) const
Expression of a fixed-size or dynamic-size block.
SymmetricBlockMatrix::Block linearTerm()
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
A Gaussian factor using the canonical parameters (information form)
DenseIndex getDim(const_iterator variable) const override
void updateHessian(HessianFactor *other) const
Contains the HessianFactor class, a general quadratic factor.
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J'th diagonal block as a self adjoint view.
KeyVector::const_iterator const_iterator
Const iterator over keys.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
DenseIndex getDim(DenseIndex block) const
Number of dimensions for variable on this diagonal block.
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))
HessianFactor(const GaussianFactorGraph &factors)
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
std::uint64_t Key
Integer nonlinear key type.
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
virtual double error(const VectorValues &c) const