Go to the documentation of this file.
44 using Dims = std::vector<Key>;
45 using Pairs = std::vector<std::pair<Key, Matrix>>;
48 JacobianFactor::JacobianFactor() :
61 throw std::invalid_argument(
62 "In JacobianFactor(const GaussianFactor& rhs), rhs is neither a JacobianFactor nor a HessianFactor");
67 Ab_(
Dims{1}, b_in.size()) {
102 if (success || maxrank ==
factor.rows() - 1) {
105 Matrix::Zero(maxrank,
Ab_.
matrix().cols());
124 throw std::invalid_argument(
125 "Error in JacobianFactor constructor input. Number of provided keys "
126 "plus one for the RHS vector must equal the number of provided "
130 if (augmentedMatrix(augmentedMatrix.
nBlocks() - 1).
cols() != 1)
131 throw std::invalid_argument(
132 "Error in JacobianFactor constructor input. The last provided "
133 "matrix block must be the RHS vector, but the last provided block "
134 "had more than one column.");
144 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
152 for (
size_t jointVarpos = 0; jointVarpos < variableSlots.size();
154 const VariableSlots::const_iterator& slots = variableSlots[jointVarpos];
158 bool foundVariable =
false;
159 for (
size_t sourceFactorI = 0; sourceFactorI < slots->second.size();
161 const size_t sourceVarpos = slots->second[sourceFactorI];
164 if (sourceFactor.
cols() > 1) {
165 foundVariable =
true;
167 sourceFactor.
begin() + sourceVarpos);
169 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
171 varDims[jointVarpos] = vardim;
174 if(!(varDims[jointVarpos] == vardim)) {
175 std::stringstream
ss;
177 " has different dimensionality of " << vardim <<
" instead of " << varDims[jointVarpos];
178 throw std::runtime_error(
ss.str());
183 varDims[jointVarpos] = vardim;
192 throw std::invalid_argument(
193 "Unable to determine dimensionality for all variables");
200 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS)
210 FastVector<JacobianFactor::shared_ptr> _convertOrCastToJacobians(
211 const GaussianFactorGraph&
factors) {
212 gttic(Convert_to_Jacobians);
213 FastVector<JacobianFactor::shared_ptr> jacobians;
219 jacobians.push_back(jf);
221 jacobians.push_back(std::make_shared<JacobianFactor>(*
factor));
237 const auto [varDims,
m,
n] = _countDims(jacobians, orderedSlots);
246 [](
const VariableSlots::const_iterator& it) {return it->first;});
251 size_t combinedSlot = 0;
252 for(VariableSlots::const_iterator varslot: orderedSlots) {
256 for (
size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
258 const size_t sourceSlot = varslot->second[factorI];
259 const DenseIndex sourceRows = jacobians[factorI]->rows();
260 if (sourceRows > 0) {
262 destSlot.middleRows(nextRow, sourceRows));
265 destBlock = jacobians[factorI]->getA(
266 jacobians[factorI]->
begin() + sourceSlot);
269 nextRow += sourceRows;
278 bool anyConstrained =
false;
279 std::optional<Vector>
sigmas;
282 for (
size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
284 if (sourceRows > 0) {
285 this->
getb().segment(nextRow, sourceRows) = jacobians[factorI]->getb();
289 sigmas = Vector::Constant(
m, 1.0);
290 sigmas->segment(nextRow, sourceRows) =
291 jacobians[factorI]->get_model()->sigmas();
293 anyConstrained =
true;
295 nextRow += sourceRows;
314 orderedSlots.reserve(variableSlots.size());
318 size_t nOrderingSlotsUsed = 0;
319 orderedSlots.resize(
ordering.size());
321 for (VariableSlots::const_iterator item = variableSlots.begin();
322 item != variableSlots.end(); ++item) {
324 inverseOrdering.find(item->first);
325 if (orderingPosition == inverseOrdering.end()) {
326 unorderedSlots.push_back(item);
328 orderedSlots[orderingPosition->second] = item;
329 ++nOrderingSlotsUsed;
332 if (nOrderingSlotsUsed !=
ordering.size())
333 throw std::invalid_argument(
334 "The ordering provided to the JacobianFactor combine constructor\n"
335 "contained extra variables that did not appear in the factors to combine.");
337 for(VariableSlots::const_iterator item: unorderedSlots) {
338 orderedSlots.push_back(item);
348 gttic(JacobianFactor_combine_constructor);
359 orderedSlots.reserve(variableSlots.size());
363 for (VariableSlots::const_iterator item = variableSlots.begin();
364 item != variableSlots.end(); ++item)
365 orderedSlots.push_back(item);
374 gttic(JacobianFactor_combine_constructor);
384 orderedSlots.reserve(variableSlots.size());
388 for (VariableSlots::const_iterator item = variableSlots.begin();
389 item != variableSlots.end(); ++item)
390 orderedSlots.push_back(item);
399 gttic(JacobianFactor_combine_constructor);
416 gttic(JacobianFactor_combine_constructor);
436 model_->print(
" Noise model: ");
438 cout <<
" No noise model" << endl;
444 static const bool verbose =
false;
447 cout <<
"JacobianFactor::equals: Incorrect type" << endl;
453 if (
keys() !=
f.keys()) {
455 cout <<
"JacobianFactor::equals: keys do not match" << endl;
462 cout <<
"JacobianFactor::equals: noise model mismatch" << endl;
467 cout <<
"JacobianFactor::equals: noise modesl are not equal" << endl;
474 cout <<
"JacobianFactor::equals: augmented size mismatch" << endl;
485 cout <<
"JacobianFactor::equals: matrix mismatch at row " <<
row << endl;
512 if (
model_)
return 0.5 *
model_->squaredMahalanobisDistance(
e);
513 return 0.5 *
e.dot(
e);
520 model_->WhitenInPlace(AbWhitened);
521 return AbWhitened.transpose() * AbWhitened;
531 model_->WhitenInPlace(AWhitened);
532 return AWhitened.transpose() * AWhitened;
534 return this->
getA().transpose() * this->
getA();
547 for (
size_t k = 0; k < nj; ++k) {
550 Vector column_k_copy = column_k;
551 model_->whitenInPlace(column_k_copy);
553 dj(k) +=
dot(column_k_copy, column_k_copy);
555 dj(k) =
dot(column_k_copy, column_k_copy);
558 dj(k) +=
dot(column_k, column_k);
560 dj(k) =
dot(column_k, column_k);
569 throw std::runtime_error(
"JacobianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
574 map<Key, Matrix> blocks;
580 blocks.emplace(
j, Aj.transpose() * Aj);
588 gttic(updateHessian_JacobianFactor);
590 if (
rows() == 0)
return;
595 if (
model->isConstrained())
596 throw invalid_argument(
597 "JacobianFactor::updateHessian: cannot update information with "
598 "constrained noise model");
606 vector<DenseIndex> slots(
n + 1);
618 info->updateOffDiagonalBlock(
I,
J,
Ab_(
i).transpose() * Ab_j);
621 info->diagonalBlock(
J).rankUpdate(Ab_j.transpose());
656 it->second.noalias() +=
Ab_(
pos).transpose() *
E;
680 const std::vector<size_t>& accumulatedDims)
const {
700 model_->whitenInPlace(Ax);
701 model_->whitenInPlace(Ax);
729 throw std::runtime_error(
"JacobianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
752 return make_pair(
A,
b);
804 std::pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr>
EliminateQR(
810 jointFactor = std::make_shared<JacobianFactor>(
factors,
keys);
811 }
catch (std::invalid_argument&) {
813 "EliminateQR was called with a request to eliminate variables that are not\n"
814 "involved in the provided factors.");
821 if (jointFactor->model_) {
825 jointFactor->model_ = jointFactor->model_->QR(
Ab.matrix());
832 size_t m =
Ab.rows(),
n =
Ab.cols() - 1;
833 size_t maxRank =
min(
m,
n);
839 jointFactor->splitConditional(
keys.size());
841 return make_pair(conditional, jointFactor);
846 gttic(JacobianFactor_splitConditional);
849 throw std::invalid_argument(
850 "JacobianFactor::splitConditional cannot be given a nullptr noise model");
853 if (nrFrontals >
size()) {
854 throw std::invalid_argument(
855 "JacobianFactor::splitConditional was requested to split off more variables than exist.");
867 const DenseIndex originalRowEnd =
Ab_.
rowEnd();
870 conditionalNoiseModel =
873 std::make_shared<GaussianConditional>(
Base::keys_, nrFrontals,
Ab_, conditionalNoiseModel);
885 if (
model_->isConstrained())
std::vector< Eigen::Index > Dims
const DenseIndex & rowEnd() const
void checkAb(const SharedDiagonal &model, const VerticalBlockMatrix &augmentedMatrix) const
Common code between VerticalBlockMatrix constructors.
static const GTSAM_EXPORT size_t Empty
Linear Factor Graph where all factors are Gaussians.
std::shared_ptr< GaussianConditional > splitConditional(size_t nrFrontals)
Conditional Gaussian Base class.
Vector unweighted_error(const VectorValues &c) const
Expression of a fixed-size or dynamic-size block.
Block< Derived, Dynamic, internal::traits< Derived >::ColsAtCompileTime, IsRowMajor > RowsBlockXpr
A Gaussian factor using the canonical parameters (information form)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
const SharedDiagonal & get_model() const
bool isConstrained() const
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
typedef and functions to augment Eigen's MatrixXd
const GaussianFactorGraph factors
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
const KeyFormatter & formatter
Block range(DenseIndex startBlock, DenseIndex endBlock)
Efficient incomplete Cholesky on rank-deficient matrices, todo: constrained Cholesky.
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
bool empty() const
Whether the factor is empty (involves zero variables).
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Variable ordering for the elimination algorithm.
const Eigen::IOFormat & matlabFormat()
GaussianFactor::shared_ptr negate() const override
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
const_iterator begin() const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
GaussianFactor::shared_ptr negate() const override
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
pair< size_t, bool > choleskyCareful(Matrix &ATA, int order)
const constBVector getb() const
Vector operator*(const VectorValues &x) const
std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > eliminate(const Ordering &keys)
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
static std::stringstream ss
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
noiseModel::Diagonal::shared_ptr model_
const DenseIndex & firstBlock() const
Exceptions that may be thrown by linear solver components.
const DenseIndex & rowStart() const
void fillTerms(const TERMS &terms, const Vector &b, const SharedDiagonal &noiseModel)
Internal function to fill blocks and set dimensions.
JacobiRotation< float > J
Vector gradient(Key key, const VectorValues &x) const override
Compute the gradient wrt a key at any values.
DenseIndex getDim(const_iterator variable) const override
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Matrix information() const override
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
VectorValues gradientAtZero() const override
A'*b for Jacobian.
friend GTSAM_EXPORT std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
static shared_ptr Create(size_t dim)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
noiseModel::Diagonal::shared_ptr SharedDiagonal
double dot(const V1 &a, const V2 &b)
Vector gradient(Key key, const VectorValues &x) const override
Matrix augmentedJacobian() const override
DenseIndex nBlocks() const
Block count.
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
const_iterator end() const
A matrix or vector expression mapping an existing array of data.
noiseModel::Diagonal::shared_ptr model
void g(const string &key, int i)
static enum @1096 ordering
Vector error_vector(const VectorValues &c) 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
const gtsam::Symbol key('X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
std::vector< std::pair< Key, Matrix > > Pairs
VariableSlots describes the structure of a combined factor in terms of where each block comes from in...
void inplace_QR(Matrix &A)
KeyVector::const_iterator const_iterator
Const iterator over keys.
FastVector< VariableSlots::const_iterator > orderedSlotsHelper(const Ordering &ordering, const VariableSlots &variableSlots)
A matrix or vector expression mapping an existing expression.
DenseIndex cols() const
Column size.
KeyVector keys_
The keys involved in this factor.
Key front() const
First key.
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
assert equality up to a tolerance
const KeyVector & keys() const
Access the factor's involved variable keys.
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
ptrdiff_t DenseIndex
The index type for Eigen objects.
const Matrix & matrix() const
void JacobianFactorHelper(const GaussianFactorGraph &graph, const FastVector< VariableSlots::const_iterator > &orderedSlots)
std::shared_ptr< This > shared_ptr
shared_ptr to this class
DenseIndex rows() const
Row size.
static DenseIndex Slot(const CONTAINER &keys, Key key)
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print with optional string
double error(const VectorValues &c) const override
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
JacobianFactor whiten() const
void setModel(bool anyConstrained, const Vector &sigmas)
Matrix augmentedJacobianUnweighted() const
Maps global variable indices to slot indices.
Matrix augmentedInformation() const override
A thin wrapper around std::map that uses boost's fast_pool_allocator.
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:01:37