Remove unused variable

release/4.3a0
Andrew Melim 2014-03-17 12:04:40 -04:00
parent da09c31c7b
commit 719592258b
1 changed files with 3 additions and 4 deletions

View File

@ -29,11 +29,10 @@ namespace gtsam { namespace partition {
typedef map<IntPair, FactorList::iterator> Connections;
// create disjoin set forest
int numNodes = keys.size();
DSFVector dsf(workspace.dsf, keys);
FactorList factors(graph.begin(), graph.end());
size_t i, nrFactors = factors.size();
size_t nrFactors = factors.size();
FactorList::iterator itEnd;
workspace.prepareDictionary(keys);
while (nrFactors) {
@ -135,7 +134,7 @@ namespace gtsam { namespace partition {
typedef list<sharedGenericFactor3D> FactorList;
FactorList factors(graph.begin(), graph.end());
size_t i, nrFactors = factors.size();
size_t nrFactors = factors.size();
FactorList::iterator itEnd;
while (nrFactors) {
@ -445,7 +444,7 @@ namespace gtsam { namespace partition {
// find the minimum constraint for cameras and landmarks
size_t minFoundConstraintsPerCamera = 10000;
size_t minFoundConstraintsPerLandmark = 10000;
for (int i=0; i<isValidCamera.size(); i++) {
if (isValidCamera[i]) {
minFoundConstraintsPerCamera = std::min(nrConstraints[i], minFoundConstraintsPerCamera);