30 std::cout <<
" Factors:" << std::endl;
50 const std::optional< std::vector<size_t> >& removeFactorIndices) {
58 gttic(augment_system);
64 for(
const auto key: newTheta.
keys()) {
74 if(removeFactorIndices)
77 gttoc(augment_system);
117 gttic(get_summarized_factors);
125 gttoc(get_summarized_factors);
138 for(
const auto key: smootherValues.
keys()) {
151 for(
const auto key: separatorValues.
keys()) {
188 gttic(insert_factors);
191 std::vector<size_t> slots;
192 slots.reserve(factors.
size());
205 slots.push_back(slot);
208 gttoc(insert_factors);
216 gttic(remove_factors);
219 for(
size_t slot: slots) {
228 gttoc(remove_factors);
262 double previousError;
265 previousError = result.
error;
268 gttic(optimizer_iteration);
276 std::cout <<
"trying lambda = " << lambda << std::endl;
285 size_t dim = key_value.second.size();
286 Matrix A = Matrix::Identity(dim,dim);
295 dampedFactorGraph.
print(
"damped");
306 std::cout <<
"linear delta norm = " << newDelta.
norm() << std::endl;
308 newDelta.
print(
"delta");
311 gttic(compute_error);
313 gttoc(compute_error);
316 std::cout <<
"next error = " << error << std::endl;
318 if(error < result.
error) {
342 std::cout <<
"Warning: Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" << std::endl;
351 gttoc(optimizer_iteration);
354 std::cout <<
"using lambda = " << lambda << std::endl;
388 if(std::dynamic_pointer_cast<LinearContainerFactor>(factor)) {
394 std::cout << keyFormatter(
key) <<
" ";
396 std::cout <<
")" << std::endl;
398 std::cout <<
"{ nullptr }" << std::endl;
408 std::cout << keyFormatter(
key) <<
" ";
410 std::cout <<
")" << std::endl;
412 std::cout <<
"{ nullptr }" << std::endl;
const gtsam::Symbol key('X', 0)
NonlinearFactorGraph smootherSummarization_
A temporary holding place for calculated smoother summarization.
static void PrintNonlinearFactor(const NonlinearFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
bool equals(const ConcurrentSmoother &rhs, double tol=1e-9) const override
void replace(size_t index, sharedFactor factor)
size_t nonlinearVariables
The number of variables that can be relinearized.
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
void print(const std::string &str="VectorValues", const KeyFormatter &formatter=DefaultKeyFormatter) const
Point2 prior(const Point2 &x)
Prior on a single pose.
noiseModel::Diagonal::shared_ptr model
static void PrintLinearFactor(const GaussianFactor::shared_ptr &factor, const std::string &indent="", const KeyFormatter &keyFormatter=DefaultKeyFormatter)
const ValueType at(Key j) const
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
double lambdaFactor
The amount by which to multiply or divide lambda when adjusting lambda (default: 10.0)
Ordering ordering_
The current ordering used to calculate the linear deltas.
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization...
const GaussianFactorGraph factors
void update(Key j, const Value &val)
VectorValues delta_
The current set of linear deltas from the linearization point.
iterator insert(const std::pair< Key, Vector > &key_value)
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
Print out graph to std::cout, with optional key formatter.
void print(const std::string &s="Concurrent Batch Smoother:\, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Values retract(const VectorValues &delta) const
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
void getSummarizedFactors(NonlinearFactorGraph &summarizedFactors, Values &separatorValues) override
double errorTol
The maximum total error to stop iterating (default 0.0)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
bool equals(const VectorValues &x, double tol=1e-9) const
VectorValues zeroVectors() const
size_t iterations
The number of optimizer iterations performed.
double error
The final factor graph error.
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const std::optional< std::vector< size_t > > &removeFactorIndices={})
VariableIndex variableIndex_
The current variable index, which allows efficient factor lookup by variable.
NonlinearFactorGraph calculateMarginalFactors(const NonlinearFactorGraph &graph, const Values &theta, const KeySet &remainingKeys, const GaussianFactorGraph::Eliminate &eliminateFunction)
value_type KeyValuePair
Typedef to pair<Key, Vector>
bool equals(const Values &other, double tol=1e-9) const
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
double error(const Values &values) const
std::vector< size_t > insertFactors(const NonlinearFactorGraph &factors)
LevenbergMarquardtParams parameters_
LM parameters.
Values theta_
Current linearization point of all variables in the smoother.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
size_t linearVariables
The number of variables that must keep a constant linearization point.
GaussianFactorGraph::Eliminate getEliminationFunction() const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoothing interface...
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
noiseModel::Diagonal::shared_ptr SharedDiagonal
GTSAM_EXPORT bool equals(const Ordering &other, double tol=1e-9) const
std::vector< size_t > filterSummarizationSlots_
The slots in factor graph that correspond to the current filter summarization factors.
NonlinearFactorGraph factors_
The set of all factors currently in the smoother.
void synchronize(const NonlinearFactorGraph &smootherFactors, const Values &smootherValues, const NonlinearFactorGraph &summarizedFactors, const Values &separatorValues) override
void updateSmootherSummarization()
std::shared_ptr< This > shared_ptr
void insert(Key j, const Value &val)
void reserve(size_t size)
Jet< T, N > sqrt(const Jet< T, N > &f)
void removeFactors(const std::vector< size_t > &slots)
double lambdaUpperBound
The maximum lambda to try before assuming the optimization has failed (default: 1e5) ...
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH &graph, const KeyVector &constrainLast, bool forceOrder=false)
std::uint64_t Key
Integer nonlinear key type.
size_t maxIterations
The maximum iterations to stop iterating (default 100)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
double lambdaInitial
The initial Levenberg-Marquardt damping term (default: 1e-5)