Add Snavely cost function
parent
7018afdd58
commit
bdf12b14b9
|
@ -271,6 +271,63 @@ struct Projective {
|
|||
}
|
||||
};
|
||||
|
||||
// Templated pinhole camera model for used with Ceres. The camera is
|
||||
// parameterized using 9 parameters: 3 for rotation, 3 for translation, 1 for
|
||||
// focal length and 2 for radial distortion. The principal point is not modeled
|
||||
// (i.e. it is assumed be located at the image center).
|
||||
struct SnavelyReprojectionError {
|
||||
SnavelyReprojectionError(double observed_x, double observed_y) :
|
||||
observed_x(observed_x), observed_y(observed_y) {
|
||||
}
|
||||
|
||||
template<typename T>
|
||||
bool operator()(const T* const camera, const T* const point,
|
||||
T* residuals) const {
|
||||
// camera[0,1,2] are the angle-axis rotation.
|
||||
T p[3];
|
||||
ceres::AngleAxisRotatePoint(camera, point, p);
|
||||
|
||||
// camera[3,4,5] are the translation.
|
||||
p[0] += camera[3];
|
||||
p[1] += camera[4];
|
||||
p[2] += camera[5];
|
||||
|
||||
// Compute the center of distortion. The sign change comes from
|
||||
// the camera model that Noah Snavely's Bundler assumes, whereby
|
||||
// the camera coordinate system has a negative z axis.
|
||||
T xp = -p[0] / p[2];
|
||||
T yp = -p[1] / p[2];
|
||||
|
||||
// Apply second and fourth order radial distortion.
|
||||
const T& l1 = camera[7];
|
||||
const T& l2 = camera[8];
|
||||
T r2 = xp * xp + yp * yp;
|
||||
T distortion = T(1.0) + r2 * (l1 + l2 * r2);
|
||||
|
||||
// Compute final projected point position.
|
||||
const T& focal = camera[6];
|
||||
T predicted_x = focal * distortion * xp;
|
||||
T predicted_y = focal * distortion * yp;
|
||||
|
||||
// The error is the difference between the predicted and observed position.
|
||||
residuals[0] = predicted_x - T(observed_x);
|
||||
residuals[1] = predicted_y - T(observed_y);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// Factory to hide the construction of the CostFunction object from
|
||||
// the client code.
|
||||
static ceres::CostFunction* Create(const double observed_x,
|
||||
const double observed_y) {
|
||||
return (new ceres::AutoDiffCostFunction<SnavelyReprojectionError, 2, 9, 3>(
|
||||
new SnavelyReprojectionError(observed_x, observed_y)));
|
||||
}
|
||||
|
||||
double observed_x;
|
||||
double observed_y;
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
// manifold_traits prototype
|
||||
#include <boost/static_assert.hpp>
|
||||
|
|
Loading…
Reference in New Issue