32 #include <boost/format.hpp> 33 #include <boost/make_shared.hpp> 34 #include <boost/tuple/tuple.hpp> 36 #pragma GCC diagnostic push 37 #pragma GCC diagnostic ignored "-Wunused-variable" 39 #include <boost/bind.hpp> 41 #pragma GCC diagnostic pop 43 #include <boost/assign/list_of.hpp> 44 #include <boost/range/adaptor/transformed.hpp> 45 #include <boost/range/adaptor/map.hpp> 46 #include <boost/range/algorithm/copy.hpp> 61 void HessianFactor::Allocate(
const Scatter& scatter) {
62 gttic(HessianFactor_Allocate);
65 const size_t n = scatter.size();
69 for(
const SlotEntry& slotentry: scatter) {
70 keys_[slot] = slotentry.key;
71 dims[slot] = slotentry.dimension;
79 HessianFactor::HessianFactor(
const Scatter& scatter) {
84 HessianFactor::HessianFactor() :
85 info_(cref_list_of<1>(1)) {
93 if (G.rows() != G.cols() || G.rows() != g.size())
94 throw invalid_argument(
95 "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
106 if (Sigma.rows() != Sigma.cols() || Sigma.rows() != mu.size())
107 throw invalid_argument(
108 "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
119 cref_list_of<3>(G11.
cols())(G22.
cols())(1)) {
133 cref_list_of<4>(G11.
cols())(G22.
cols())(G33.
cols())(1)) {
134 if (G11.rows() != G11.cols() || G11.rows() != G12.rows()
135 || G11.rows() != G13.rows() || G11.rows() != g1.size()
136 || G22.cols() != G12.cols() || G33.cols() != G13.cols()
137 || G22.cols() != g2.size() || G33.cols() != g3.size())
138 throw invalid_argument(
139 "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
159 const std::vector<Matrix>& Gs,
const std::vector<Vector>& gs,
double f) :
162 size_t variable_count = js.size();
165 if (gs.size() != variable_count
166 || Gs.size() != (variable_count * (variable_count + 1)) / 2)
167 throw invalid_argument(
168 "Inconsistent number of entries between js, Gs, and gs in HessianFactor constructor.\nThe number of keys provided \ 169 in js must match the number of linear vector pieces in gs. The number of upper-diagonal blocks in Gs must be n*(n+1)/2");
173 for (
size_t i = 0;
i < variable_count; ++
i) {
176 for (
size_t j = 0;
j < variable_count -
i; ++
j) {
177 size_t index = i * (2 * variable_count - i + 1) / 2 +
j;
178 if (Gs[index].
rows() != block_size) {
179 throw invalid_argument(
180 "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
184 for (
size_t j = 0;
j <=
i; ++
j) {
185 size_t index =
j * (2 * variable_count -
j + 1) / 2 + (i -
j);
186 if (Gs[index].
cols() != block_size) {
187 throw invalid_argument(
188 "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
195 for (
size_t i = 0;
i < variable_count; ++
i) {
196 for (
size_t j =
i;
j < variable_count; ++
j) {
212 gttic(HessianFactor_fromJacobian);
217 throw invalid_argument(
218 "Cannot construct HessianFactor from JacobianFactor with constrained noise model");
220 auto D = (jfModel->invsigmas().array() * jfModel->invsigmas().array()).
matrix().asDiagonal();
233 _FromJacobianHelper(jf,
info_);
240 if (
const JacobianFactor* jf = dynamic_cast<const JacobianFactor*>(&gf)) {
242 _FromJacobianHelper(*jf,
info_);
243 }
else if (
const HessianFactor* hf = dynamic_cast<const HessianFactor*>(&gf)) {
246 throw std::invalid_argument(
247 "In HessianFactor(const GaussianFactor& gf), gf is neither a JacobianFactor nor a HessianFactor");
254 gttic(HessianFactor_MergeConstructor);
261 for(
const auto& factor: factors)
276 "Augmented information matrix: ");
318 throw std::runtime_error(
319 "HessianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
324 map<Key, Matrix> blocks;
350 double xtg = 0, xGx = 0;
356 xGx = x.transpose() * AtA *
x;
357 return 0.5 * (f - 2.0 * xtg + xGx);
363 gttic(updateHessian_HessianFactor);
367 vector<DenseIndex> slots(nrVariablesInThisFactor + 1);
371 const bool rhs = (
j == nrVariablesInThisFactor);
393 result->info_.negate();
405 y.push_back(Vector::Zero(
getDim(it)));
430 it->second = alpha * y[
i];
432 it->second += alpha * y[
i];
440 for (
size_t j = 0;
j <
n; ++
j)
448 throw std::runtime_error(
449 "HessianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
458 Vector b = Vector::Zero(x.
at(key).size());
466 b += Gij * x.
at(*it_j);
475 gttic(HessianFactor_eliminateCholesky);
481 size_t nFrontals = keys.size();
482 assert(nFrontals <=
size());
487 conditional = boost::make_shared<GaussianConditional>(
keys_, nFrontals,
Ab);
493 cout <<
"Partial Cholesky on HessianFactor failed." << endl;
494 keys.
print(
"Frontal keys ");
495 print(
"HessianFactor:");
506 gttic(HessianFactor_solve);
509 const size_t n =
size();
516 const Vector solution =
R.solve(eta);
531 std::pair<boost::shared_ptr<GaussianConditional>, boost::shared_ptr<HessianFactor> >
538 Scatter scatter(factors, keys);
539 jointFactor = boost::make_shared<HessianFactor>(
factors, scatter);
540 }
catch (std::invalid_argument&) {
542 "EliminateCholesky was called with a request to eliminate variables that are not\n" 543 "involved in the provided factors.");
547 auto conditional = jointFactor->eliminateCholesky(keys);
550 return make_pair(conditional, jointFactor);
554 std::pair<boost::shared_ptr<GaussianConditional>,
void print(const Matrix &A, const string &s, ostream &stream)
One SlotEntry stores the slot index for a variable, as well its dim.
bool equals(const This &other, double tol=1e-9) const
check equality
SymmetricBlockMatrix::constBlock linearTerm() const
VectorValues gradientAtZero() const override
eta for Hessian
const VerticalBlockMatrix & matrixObject() const
VectorValues solve()
Solve the system A'*A delta = A'*b in-place, return delta as VectorValues.
Values::iterator iterator
Iterator over vector values.
const_iterator find(Key key) const
find
Eigen::SelfAdjointView< SymmetricBlockMatrix::constBlock, Eigen::Upper > informationView() const
Return self-adjoint view onto the information matrix (NOT augmented).
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated. ...
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
JacobiRotation< float > G
A factor with a quadratic error function - a Gaussian.
Rot2 R(Rot2::fromAngle(0.1))
const_iterator end() const
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 offset
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
KeyVector keys_
The keys involved in this factor.
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
static SymmetricBlockMatrix LikeActiveViewOf(const SymmetricBlockMatrix &other)
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
const KeyFormatter & formatter
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Matrix augmentedInformation() const override
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
double error(const VectorValues &c) const override
double constantTerm() const
void Allocate(const Scatter &scatter)
Allocate for given scatter pattern.
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< HessianFactor > > EliminateCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
bool empty() const override
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
const_iterator begin() const
Vector diagonal(DenseIndex J) const
Get the diagonal of the J'th diagonal block.
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Matrix information() const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Contains the HessianFactor class, a general quadratic factor.
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr...
Expression of a selfadjoint matrix from a triangular part of a dense matrix.
Matrix augmentedJacobian() const override
Conditional Gaussian Base class.
Linear Factor Graph where all factors are Gaussians.
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
boost::shared_ptr< GaussianConditional > eliminateCholesky(const Ordering &keys)
JacobiRotation< float > J
Eigen::TriangularView< constBlock, Eigen::Upper > triangularView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j) as a triangular view. ...
SymmetricBlockMatrix info_
The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'H[x -1]...
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
GaussianFactor::shared_ptr negate() const override
Exceptions that may be thrown by linear solver components.
const SharedDiagonal & get_model() const
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
void setFullMatrix(const XprType &xpr)
Set the entire active matrix. Only reads the upper triangular part of xpr.
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
noiseModel::Diagonal::shared_ptr SharedDiagonal
Matrix block(DenseIndex I, DenseIndex J) const
VerticalBlockMatrix split(DenseIndex nFrontals)
A thin wrapper around std::map that uses boost's fast_pool_allocator.
bool hasConstraints(const GaussianFactorGraph &factors)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
const KeyVector & keys() const
Access the factor's involved variable keys.
std::pair< Matrix, Vector > jacobian() const override
Return (dense) matrix associated with factor.
void choleskyPartial(DenseIndex nFrontals)
void setZero()
Set the entire active matrix zero.
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Matrix augmentedJacobian() const override
A Gaussian factor using the canonical parameters (information form)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
DenseIndex getDim(const_iterator variable) const override
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Indicate Cholesky factorization failure.
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
DenseIndex getDim(DenseIndex block) const
Number of dimensions for variable on this diagonal block.
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.
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
Vector gradient(Key key, const VectorValues &x) const override
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
DenseIndex nBlocks() const
Block count.
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
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))
DenseIndex rows() const
Row size.
static DenseIndex Slot(const CONTAINER &keys, Key key)
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
std::uint64_t Key
Integer nonlinear key type.
GTSAM_EXPORT void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Efficient incomplete Cholesky on rank-deficient matrices, todo: constrained Cholesky.