42 return e !=
nullptr && FixedLagSmoother::equals(*e, tol)
49 "BatchFixedLagSmoother::marginalCovariance not implemented");
58 gttic(augment_system);
60 theta_.insert(newTheta);
62 for (
const auto key_value : newTheta) {
63 ordering_.push_back(key_value.key);
66 delta_.insert(newTheta.zeroVectors());
69 insertFactors(newFactors);
70 gttoc(augment_system);
73 for(
const size_t i : factorsToRemove){
79 updateKeyTimestampMap(timestamps);
82 double current_timestamp = getCurrentTimestamp();
85 KeyVector marginalizableKeys = findKeysBefore(
86 current_timestamp - smootherLag_);
90 reorder(marginalizableKeys);
96 if (factors_.size() > 0) {
103 if (marginalizableKeys.size() > 0) {
104 marginalize(marginalizableKeys);
112 void BatchFixedLagSmoother::insertFactors(
114 for(
const auto& factor: newFactors) {
117 if (availableSlots_.size() > 0) {
118 index = availableSlots_.front();
119 availableSlots_.pop();
120 factors_.replace(index, factor);
122 index = factors_.size();
123 factors_.push_back(factor);
127 factorIndex_[
key].insert(index);
133 void BatchFixedLagSmoother::removeFactors(
134 const set<size_t>& deleteFactors) {
135 for(
size_t slot: deleteFactors) {
136 if (factors_.at(slot)) {
138 for(
Key key: *(factors_.at(slot))) {
139 factorIndex_[
key].erase(slot);
142 factors_.remove(slot);
144 availableSlots_.push(slot);
147 cout <<
"Attempting to remove a factor from slot " << slot
148 <<
", but it is already nullptr." << endl;
161 factorIndex_.erase(
key);
164 if (linearKeys_.exists(
key)) {
165 linearKeys_.erase(
key);
169 eraseKeyTimestampMap(keys);
173 ordering_.erase(find(ordering_.begin(), ordering_.end(),
key));
179 void BatchFixedLagSmoother::reorder(
const KeyVector& marginalizeKeys) {
181 ordering_ = Ordering::ColamdConstrainedFirst(factors_, marginalizeKeys);
193 double lambda = parameters_.lambdaInitial;
194 double lambdaFactor = parameters_.lambdaFactor;
195 double lambdaUpperBound = parameters_.lambdaUpperBound;
196 double lambdaLowerBound = 1.0e-10;
198 double relativeErrorTol = parameters_.relativeErrorTol;
199 double absoluteErrorTol = parameters_.absoluteErrorTol;
200 double errorTol = parameters_.errorTol;
204 result.
error = factors_.error(evalpoint);
207 if (result.
error <= errorTol) {
212 double previousError;
215 previousError = result.
error;
218 gttic(optimizer_iteration);
229 dampedFactorGraph.
reserve(linearFactorGraph.
size() + delta_.size());
233 for(
const auto& key_value: delta_) {
234 size_t dim = key_value.second.size();
235 Matrix A = Matrix::Identity(dim, dim);
248 newDelta = dampedFactorGraph.
optimize(ordering_,
249 parameters_.getEliminationFunction());
251 evalpoint = theta_.
retract(newDelta);
255 gttic(compute_error);
256 double error = factors_.error(evalpoint);
257 gttoc(compute_error);
259 if (error < result.
error) {
268 if (enforceConsistency_ && (linearKeys_.size() > 0)) {
269 theta_.
update(linearKeys_);
270 for(
const auto key_value: linearKeys_) {
271 delta_.at(key_value.key) = newDelta.
at(key_value.key);
275 lambda /= lambdaFactor;
276 if (lambda < lambdaLowerBound) {
277 lambda = lambdaLowerBound;
283 if (lambda >= lambdaUpperBound) {
286 <<
"Warning: Levenberg-Marquardt giving up because cannot decrease error with maximum lambda" 291 lambda *= lambdaFactor;
296 gttoc(optimizer_iteration);
301 previousError, result.
error, NonlinearOptimizerParams::SILENT));
307 void BatchFixedLagSmoother::marginalize(
const KeyVector& marginalizeKeys) {
315 set<size_t> removedFactorSlots;
317 for(
Key key: marginalizeKeys) {
318 const auto& slots = variableIndex[
key];
319 removedFactorSlots.insert(slots.begin(), slots.end());
324 for(
size_t slot: removedFactorSlots) {
325 if (factors_.at(slot)) {
326 removedFactors.
push_back(factors_.at(slot));
332 removedFactors, theta_, marginalizeKeys, parameters_.getEliminationFunction());
335 removeFactors(removedFactorSlots);
338 eraseKeys(marginalizeKeys);
341 insertFactors(marginalFactors);
346 const string& label) {
356 const string& label) {
365 void BatchFixedLagSmoother::PrintSymbolicFactor(
369 for(
Key key: factor->keys()) {
375 cout <<
" )" << endl;
379 void BatchFixedLagSmoother::PrintSymbolicFactor(
382 for(
Key key: factor->keys()) {
385 cout <<
" )" << endl;
389 void BatchFixedLagSmoother::PrintSymbolicGraph(
391 cout << label << endl;
392 for(
const auto& factor: graph) {
393 PrintSymbolicFactor(factor);
399 const string& label) {
400 cout << label << endl;
401 for(
const auto& factor: graph) {
402 PrintSymbolicFactor(factor);
410 if (keys.size() == 0) {
423 if (keys.size() == 0) {
428 const auto linearFactorGraph = graph.
linearize(theta);
430 const auto marginalLinearFactors =
431 CalculateMarginalFactors(*linearFactorGraph, keys, eliminateFunction);
434 return LinearContainerFactor::ConvertLinearGraph(marginalLinearFactors, theta);
void print(const Matrix &A, const string &s, ostream &stream)
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
size_t iterations
The number of optimizer iterations performed.
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
size_t linearVariables
The number of variables that must keep a constant linearization point.
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
double error
The final factor graph error.
Point2 prior(const Point2 &x)
Prior on a single pose.
noiseModel::Diagonal::shared_ptr model
FastVector< FactorIndex > FactorIndices
Define collection types:
static const double sigma
A factor with a quadratic error function - a Gaussian.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Values retract(const VectorValues &delta) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
static const KeyFormatter DefaultKeyFormatter
size_t intermediateSteps
The number of intermediate steps performed within the optimization. For L-M, this is the number of la...
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
bool checkConvergence(double relativeErrorTreshold, double absoluteErrorTreshold, double errorThreshold, double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity)
An LM-based fixed-lag smoother.
boost::shared_ptr< This > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
size_t nonlinearVariables
The number of variables that can be relinearized.
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
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
noiseModel::Diagonal::shared_ptr SharedDiagonal
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
void update(Key j, const Value &val)
void reserve(size_t size)
NonlinearFactorGraph factors_
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
std::uint64_t Key
Integer nonlinear key type.
bool equals(const FixedLagSmoother &rhs, double tol=1e-9) const override