Skip to content

Commit

Permalink
Rejecting last loop closures if optimization fails. Fixed _lastLocali…
Browse files Browse the repository at this point in the history
…zationNodeId not found in optimized poses in Localization mode.
  • Loading branch information
matlabbe committed Dec 1, 2015
1 parent 4d97ba8 commit 60f34fe
Show file tree
Hide file tree
Showing 2 changed files with 42 additions and 4 deletions.
16 changes: 16 additions & 0 deletions corelib/src/Graph.cpp
Expand Up @@ -958,6 +958,8 @@ std::map<int, Transform> G2OOptimizer::optimize(
UDEBUG("Initial optimization...");
optimizer.initializeOptimization();

UASSERT(optimizer.verifyInformationMatrices());

UINFO("g2o optimizing begin (max iterations=%d, robust=%d)", iterations(), isRobust()?1:0);
int it = 0;
UTimer timer;
Expand Down Expand Up @@ -1017,6 +1019,14 @@ std::map<int, Transform> G2OOptimizer::optimize(
optimizer.computeActiveErrors();
double chi2 = optimizer.activeRobustChi2();
UDEBUG("iteration %d: %d nodes, %d edges, chi2: %f", i, (int)optimizer.vertices().size(), (int)optimizer.edges().size(), chi2);

if(i>0 && optimizer.activeRobustChi2() > 1000000000000.0)
{
UWARN("g2o: Large optimimzation error detected (%f), aborting optimization!");
return optimizedPoses;
}


double errorDelta = lastError - chi2;
if(i>0 && errorDelta < this->epsilon())
{
Expand Down Expand Up @@ -1054,6 +1064,12 @@ std::map<int, Transform> G2OOptimizer::optimize(
}
UINFO("g2o optimizing end (%d iterations done, error=%f, time = %f s)", it, optimizer.activeRobustChi2(), timer.ticks());

if(optimizer.activeRobustChi2() > 1000000000000.0)
{
UWARN("g2o: Large optimimzation error detected (%f), aborting optimization!");
return optimizedPoses;
}

if(isSlam2d())
{
for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
Expand Down
30 changes: 26 additions & 4 deletions corelib/src/Rtabmap.cpp
Expand Up @@ -2213,12 +2213,24 @@ bool Rtabmap::process(
std::map<int, Transform> poses = _optimizedPoses;
std::multimap<int, Link> constraints;
optimizeCurrentMap(signature->id(), false, poses, &constraints, &optimizationError, &optimizationIterations);
UASSERT(poses.find(signature->id()) != poses.end());

// Check added loop closures have broken the graph
// (in case of wrong loop closures).
bool updateConstraints = true;
if(_memory->isIncremental() && // FIXME: not tested in localization mode, so do it only in mapping mode
if(poses.empty())
{
UWARN("Graph optimization failed! Rejecting last loop closures added.");
for(std::list<std::pair<int, int> >::iterator iter=loopClosureLinksAdded.begin(); iter!=loopClosureLinksAdded.end(); ++iter)
{
_memory->removeLink(iter->first, iter->second);
UWARN("Loop closure %d->%d rejected!", iter->first, iter->second);
}
updateConstraints = false;
_loopClosureHypothesis.first = 0;
lastLocalSpaceClosureId = 0;
rejectedHypothesis = true;
}
else if(_memory->isIncremental() && // FIXME: not tested in localization mode, so do it only in mapping mode
_optimizationMaxLinearError > 0.0f &&
loopClosureLinksAdded.size())
{
Expand Down Expand Up @@ -2498,7 +2510,7 @@ bool Rtabmap::process(
}
else
{
UASSERT_MSG(uContains(_optimizedPoses, _lastLocalizationNodeId), uFormat("id=%d", _lastLocalizationNodeId).c_str());
UASSERT_MSG(uContains(_optimizedPoses, _lastLocalizationNodeId), uFormat("id=%d isInWM?=%d", _lastLocalizationNodeId, _memory->isInWM(_lastLocalizationNodeId)?1:0).c_str());
id = _lastLocalizationNodeId;
UDEBUG("Refresh local map from %d", id);
}
Expand All @@ -2512,13 +2524,18 @@ bool Rtabmap::process(
}
if(id > 0)
{
if(_lastLocalizationNodeId != 0)
{
_lastLocalizationNodeId = id;
}
UASSERT_MSG(_memory->getSignature(id) != 0, uFormat("id=%d", id).c_str());
std::map<int, int> ids = _memory->getNeighborsId(id, 0, 0, true);
for(std::map<int, Transform>::iterator iter=_optimizedPoses.begin(); iter!=_optimizedPoses.end();)
{
if(!uContains(ids, iter->first))
{
UDEBUG("Removed %d from local map", iter->first);
UASSERT(iter->first != _lastLocalizationNodeId);
_optimizedPoses.erase(iter++);
}
else
Expand Down Expand Up @@ -2957,7 +2974,12 @@ void Rtabmap::optimizeCurrentMap(
}
else
{
UERROR("Failed to optimize the graph! Keeping the graph without optimization...");
UERROR("Failed to optimize the graph! returning empty optimized poses...");
optimizedPoses.clear();
if(constraints)
{
constraints->clear();
}
}
}
}
Expand Down

0 comments on commit 60f34fe

Please sign in to comment.