34 #include <boost/assign/list_of.hpp> 35 #include <boost/format.hpp> 36 #include <boost/make_shared.hpp> 37 #include <boost/array.hpp> 39 #pragma GCC diagnostic push 40 #pragma GCC diagnostic ignored "-Wunused-variable" 42 #include <boost/bind.hpp> 44 #pragma GCC diagnostic pop 46 #include <boost/range/algorithm/copy.hpp> 47 #include <boost/range/adaptor/indirected.hpp> 48 #include <boost/range/adaptor/map.hpp> 60 JacobianFactor::JacobianFactor() :
61 Ab_(cref_list_of<1>(1), 0) {
68 if (
const JacobianFactor* asJacobian = dynamic_cast<const JacobianFactor*>(&gf))
70 else if (
const HessianFactor* asHessian = dynamic_cast<const HessianFactor*>(&gf))
73 throw std::invalid_argument(
74 "In JacobianFactor(const GaussianFactor& rhs), rhs is neither a JacobianFactor nor a HessianFactor");
79 Ab_(cref_list_of<1>(1), b_in.
size()) {
86 fillTerms(cref_list_of<1>(make_pair(i1, A1)), b, model);
92 fillTerms(cref_list_of<2>(make_pair(i1, A1))(make_pair(i2, A2)), b, model);
100 cref_list_of<3>(make_pair(i1, A1))(make_pair(i2, A2))(make_pair(i3, A3)),
118 if (success || maxrank == factor.
rows() - 1) {
121 Matrix::Zero(maxrank,
Ab_.
matrix().cols());
134 boost::tuple<FastVector<DenseIndex>,
DenseIndex, DenseIndex> _countDims(
138 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 146 for (
size_t jointVarpos = 0; jointVarpos < variableSlots.size();
148 const VariableSlots::const_iterator& slots = variableSlots[jointVarpos];
150 assert(slots->second.size() == factors.size());
152 bool foundVariable =
false;
153 for (
size_t sourceFactorI = 0; sourceFactorI < slots->second.size();
155 const size_t sourceVarpos = slots->second[sourceFactorI];
158 if (sourceFactor.
cols() > 1) {
159 foundVariable =
true;
160 DenseIndex vardim = sourceFactor.
getDim(
161 sourceFactor.
begin() + sourceVarpos);
163 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 165 varDims[jointVarpos] = vardim;
168 if(!(varDims[jointVarpos] == vardim)) {
169 std::stringstream
ss;
171 " has different dimensionality of " << vardim <<
" instead of " << varDims[jointVarpos];
172 throw std::runtime_error(ss.str());
177 varDims[jointVarpos] = vardim;
186 throw std::invalid_argument(
187 "Unable to determine dimensionality for all variables");
194 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) 195 for(DenseIndex
d: varDims) {
206 gttic(Convert_to_Jacobians);
208 jacobians.reserve(factors.
size());
213 jacobians.push_back(jf);
215 jacobians.push_back(boost::make_shared<JacobianFactor>(*factor));
233 boost::tie(varDims, m, n) = _countDims(jacobians, orderedSlots);
241 orderedSlots | boost::adaptors::indirected | boost::adaptors::map_keys,
247 size_t combinedSlot = 0;
248 for(VariableSlots::const_iterator varslot: orderedSlots) {
252 for (
size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
254 const size_t sourceSlot = varslot->second[factorI];
255 const DenseIndex sourceRows = jacobians[factorI]->rows();
256 if (sourceRows > 0) {
258 destSlot.middleRows(nextRow, sourceRows));
261 destBlock = jacobians[factorI]->getA(
262 jacobians[factorI]->
begin() + sourceSlot);
265 nextRow += sourceRows;
274 bool anyConstrained =
false;
275 boost::optional<Vector>
sigmas;
278 for (
size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
279 const DenseIndex sourceRows = jacobians[factorI]->rows();
280 if (sourceRows > 0) {
281 this->
getb().segment(nextRow, sourceRows) = jacobians[factorI]->getb();
285 sigmas = Vector::Constant(m, 1.0);
286 sigmas->segment(nextRow, sourceRows) =
287 jacobians[factorI]->get_model()->sigmas();
289 anyConstrained =
true;
291 nextRow += sourceRows;
297 this->
setModel(anyConstrained, *sigmas);
310 orderedSlots.reserve(variableSlots.size());
314 size_t nOrderingSlotsUsed = 0;
315 orderedSlots.resize(ordering.size());
317 for (VariableSlots::const_iterator item = variableSlots.begin();
318 item != variableSlots.end(); ++item) {
320 inverseOrdering.find(item->first);
321 if (orderingPosition == inverseOrdering.end()) {
322 unorderedSlots.push_back(item);
324 orderedSlots[orderingPosition->second] = item;
325 ++nOrderingSlotsUsed;
328 if (nOrderingSlotsUsed != ordering.size())
329 throw std::invalid_argument(
330 "The ordering provided to the JacobianFactor combine constructor\n" 331 "contained extra variables that did not appear in the factors to combine.");
333 for(VariableSlots::const_iterator item: unorderedSlots) {
334 orderedSlots.push_back(item);
344 gttic(JacobianFactor_combine_constructor);
355 orderedSlots.reserve(variableSlots.size());
359 for (VariableSlots::const_iterator item = variableSlots.begin();
360 item != variableSlots.end(); ++item)
361 orderedSlots.push_back(item);
370 gttic(JacobianFactor_combine_constructor);
380 orderedSlots.reserve(variableSlots.size());
384 for (VariableSlots::const_iterator item = variableSlots.begin();
385 item != variableSlots.end(); ++item)
386 orderedSlots.push_back(item);
395 gttic(JacobianFactor_combine_constructor);
412 gttic(JacobianFactor_combine_constructor);
432 model_->print(
" Noise model: ");
434 cout <<
" No noise model" << endl;
440 static const bool verbose =
false;
441 if (!dynamic_cast<const JacobianFactor*>(&f_)) {
443 cout <<
"JacobianFactor::equals: Incorrect type" << endl;
451 cout <<
"JacobianFactor::equals: keys do not match" << endl;
458 cout <<
"JacobianFactor::equals: noise model mismatch" << endl;
463 cout <<
"JacobianFactor::equals: noise modesl are not equal" << endl;
470 cout <<
"JacobianFactor::equals: augmented size mismatch" << endl;
481 cout <<
"JacobianFactor::equals: matrix mismatch at row " <<
row << endl;
508 if (
model_)
return 0.5 *
model_->squaredMahalanobisDistance(e);
509 return 0.5 * e.dot(e);
516 model_->WhitenInPlace(AbWhitened);
517 return AbWhitened.transpose() * AbWhitened;
527 model_->WhitenInPlace(AWhitened);
528 return AWhitened.transpose() * AWhitened;
530 return this->
getA().transpose() * this->
getA();
543 for (
size_t k = 0; k < nj; ++k) {
546 Vector column_k_copy = column_k;
547 model_->whitenInPlace(column_k_copy);
549 dj(k) +=
dot(column_k_copy, column_k_copy);
551 dj(k) =
dot(column_k_copy, column_k_copy);
554 dj(k) +=
dot(column_k, column_k);
556 dj(k) =
dot(column_k, column_k);
565 throw std::runtime_error(
"JacobianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
570 map<Key, Matrix> blocks;
576 blocks.emplace(j, Aj.transpose() * Aj);
584 gttic(updateHessian_JacobianFactor);
586 if (
rows() == 0)
return;
590 if (model && !model->isUnit()) {
591 if (model->isConstrained())
592 throw invalid_argument(
593 "JacobianFactor::updateHessian: cannot update information with " 594 "constrained noise model");
603 vector<DenseIndex> slots(n+1);
640 E.noalias() = alpha *
e;
649 it->second.noalias() +=
Ab_(
pos).transpose() *
E;
673 const std::vector<size_t>& accumulatedDims)
const {
689 Ax +=
Ab_(
pos) * ConstVectorMap(x + offset, dim);
693 model_->whitenInPlace(Ax);
694 model_->whitenInPlace(Ax);
704 VectorMap(y + offset, dim) +=
Ab_(
pos).transpose() * Ax;
722 throw std::runtime_error(
"JacobianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
737 model_->WhitenSystem(result.first, result.second);
745 return make_pair(
A, b);
752 model_->WhitenInPlace(Ab);
788 if ((
size_t) sigmas.size() != this->
rows())
797 std::pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr>
EliminateQR(
803 jointFactor = boost::make_shared<JacobianFactor>(
factors,
keys);
804 }
catch (std::invalid_argument&) {
806 "EliminateQR was called with a request to eliminate variables that are not\n" 807 "involved in the provided factors.");
814 if (jointFactor->model_) {
818 jointFactor->model_ = jointFactor->model_->QR(Ab.
matrix());
826 size_t maxRank =
min(m,
n);
831 GaussianConditional::shared_ptr conditional =
832 jointFactor->splitConditional(keys.size());
834 return make_pair(conditional, jointFactor);
839 gttic(JacobianFactor_splitConditional);
842 throw std::invalid_argument(
843 "JacobianFactor::splitConditional cannot be given a nullptr noise model");
846 if (nrFrontals >
size()) {
847 throw std::invalid_argument(
848 "JacobianFactor::splitConditional was requested to split off more variables than exist.");
863 conditionalNoiseModel =
865 GaussianConditional::shared_ptr conditional =
866 boost::make_shared<GaussianConditional>(
Base::keys_, nrFrontals,
Ab_, conditionalNoiseModel);
869 std::min(Ab_.cols(), originalRowEnd) - Ab_.rowStart() - frontalDim;
871 Ab_.rowStart() += frontalDim;
872 Ab_.rowEnd() = Ab_.rowStart() + remainingRows;
873 Ab_.firstBlock() += nrFrontals;
878 if (
model_->isConstrained())
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
void inplace_QR(Matrix &A)
void fillTerms(const TERMS &terms, const Vector &b, const SharedDiagonal &noiseModel)
Internal function to fill blocks and set dimensions.
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Vector unweighted_error(const VectorValues &c) const
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
Vector operator*(const VectorValues &x) const
double dot(const V1 &a, const V2 &b)
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
std::pair< boost::shared_ptr< GaussianConditional >, shared_ptr > eliminate(const Ordering &keys)
noiseModel::Diagonal::shared_ptr model
Vector gradient(Key key, const VectorValues &x) const override
Compute the gradient wrt a key at any values.
static enum @843 ordering
A matrix or vector expression mapping an existing array of data.
const Matrix & matrix() const
noiseModel::Diagonal::shared_ptr model_
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::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
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))
iterator end()
Iterator over variables.
Block< Derived, Dynamic, internal::traits< Derived >::ColsAtCompileTime, IsRowMajor > RowsBlockXpr
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
const KeyFormatter & formatter
static shared_ptr Create(size_t dim)
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
VariableSlots describes the structure of a combined factor in terms of where each block comes from in...
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
const Eigen::IOFormat & matlabFormat()
void add(const GaussianFactor &factor)
const DenseIndex & rowStart() const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
DenseIndex nBlocks() const
Block count.
Tuple< Args... > make_tuple(Args...args)
Creates a tuple object, deducing the target type from the types of arguments.
const constBVector getb() const
Vector error_vector(const VectorValues &c) const
const_iterator begin() const
const DenseIndex & rowEnd() const
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 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Matrix augmentedJacobian() const override
bool empty() const override
DenseIndex getDim(const_iterator variable) const override
Conditional Gaussian Base class.
Linear Factor Graph where all factors are Gaussians.
static GTSAM_EXPORT const size_t Empty
JacobiRotation< float > J
JacobianFactor whiten() const
void JacobianFactorHelper(const GaussianFactorGraph &graph, const FastVector< VariableSlots::const_iterator > &orderedSlots)
void setModel(bool anyConstrained, const Vector &sigmas)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
GaussianFactor::shared_ptr negate() const override
Maps global variable indices to slot indices.
Exceptions that may be thrown by linear solver components.
static std::stringstream ss
const SharedDiagonal & get_model() const
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Block range(DenseIndex startBlock, DenseIndex endBlock)
A matrix or vector expression mapping an existing expression.
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
noiseModel::Diagonal::shared_ptr SharedDiagonal
A thin wrapper around std::map that uses boost's fast_pool_allocator.
bool isConstrained() const
Matrix augmentedJacobianUnweighted() const
Expression of a fixed-size or dynamic-size block.
const KeyVector & keys() const
Access the factor's involved variable keys.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Matrix augmentedInformation() const override
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
double error(const VectorValues &c) const override
A Gaussian factor using the canonical parameters (information form)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
FastMap< Key, size_t > invert() const
Invert (not reverse) the ordering - returns a map from key to order position.
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
FastVector< VariableSlots::const_iterator > orderedSlotsHelper(const Ordering &ordering, const VariableSlots &variableSlots)
int EIGEN_BLAS_FUNC() copy(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
boost::shared_ptr< GaussianConditional > splitConditional(size_t nrFrontals)
pair< size_t, bool > choleskyCareful(Matrix &ATA, int order)
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.
DenseIndex cols() const
Column size.
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Vector gradient(Key key, const VectorValues &x) const override
VectorValues gradientAtZero() const override
A'*b for Jacobian.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
DenseIndex nBlocks() const
Block count.
GaussianFactor::shared_ptr negate() const override
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
static DenseIndex Slot(const CONTAINER &keys, Key key)
std::uint64_t Key
Integer nonlinear key type.
Matrix information() const override
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
friend GTSAM_EXPORT std::pair< boost::shared_ptr< GaussianConditional >, shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Efficient incomplete Cholesky on rank-deficient matrices, todo: constrained Cholesky.
DenseIndex rows() const
Row size.