tiny fix to return vector of dim 3 instead 2
parent
608498ce89
commit
a3b001be36
|
|
@ -110,11 +110,10 @@ public:
|
||||||
/// shorthand for a smart pointer to a factor
|
/// shorthand for a smart pointer to a factor
|
||||||
typedef boost::shared_ptr<This> shared_ptr;
|
typedef boost::shared_ptr<This> shared_ptr;
|
||||||
|
|
||||||
/// shorthand for a pinhole camera
|
/// shorthand for a StereoCamera // TODO: Get rid of this?
|
||||||
// TODO: Switch to stereoCamera:
|
|
||||||
typedef StereoCamera Camera;
|
typedef StereoCamera Camera;
|
||||||
// typedef StereoCamera Camera;
|
|
||||||
|
|
||||||
|
/// Vector of cameras
|
||||||
typedef std::vector<Camera> Cameras;
|
typedef std::vector<Camera> Cameras;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
@ -278,6 +277,7 @@ public:
|
||||||
}
|
}
|
||||||
i += 1;
|
i += 1;
|
||||||
}
|
}
|
||||||
|
std::cout << "totalReprojError error: " << totalReprojError << std::endl;
|
||||||
// we discard smart factors that have large reprojection error
|
// we discard smart factors that have large reprojection error
|
||||||
if(dynamicOutlierRejectionThreshold_ > 0 &&
|
if(dynamicOutlierRejectionThreshold_ > 0 &&
|
||||||
totalReprojError/m > dynamicOutlierRejectionThreshold_)
|
totalReprojError/m > dynamicOutlierRejectionThreshold_)
|
||||||
|
|
@ -612,7 +612,7 @@ public:
|
||||||
if (nonDegenerate)
|
if (nonDegenerate)
|
||||||
return reprojectionError(myCameras);
|
return reprojectionError(myCameras);
|
||||||
else
|
else
|
||||||
return zero(myCameras.size() * 2);
|
return zero(myCameras.size() * 3);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue