33 using namespace gtsam;
36 static double fov = 60;
37 static size_t w=640,
h=480;
59 TestProjectionFactor factor(measurement,
model,
X(1),
T(1),
L(1),
K(1));
78 TestProjectionFactor factor(measurement,
model,
X(1),
T(1),
L(1),
K(1));
99 TestProjectionFactor factor(measurement,
model,
X(1),
T(1),
L(1),
K(1));
119 TestProjectionFactor factor(measurement,
model,
X(1),
T(1),
L(1),
K(1));
126 Matrix H1Actual, H2Actual, H3Actual, H4Actual;
130 Matrix H1Expected = (
Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.).finished();
131 Matrix H3Expected = (
Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.).finished();
138 Matrix H2Expected = numericalDerivative11<Vector, Pose3>(
139 [&factor, &
point, &
pose](
const Pose3& pose_arg) {
return factor.evaluateError(pose, pose_arg, point, *
K1); },
142 Matrix H4Expected = numericalDerivative11<Vector, Cal3_S2>(
143 [&factor, &
point, &
pose](
const Cal3_S2& K_arg) {
return factor.evaluateError(pose,
Pose3(), point, K_arg); },
155 TestProjectionFactor factor(measurement,
model,
X(1),
T(1),
L(1),
K(1));
162 Matrix H1Actual, H2Actual, H3Actual, H4Actual;
163 factor.
evaluateError(pose, body_P_sensor, point, *
K1, H1Actual, H2Actual, H3Actual, H4Actual);
166 Matrix H1Expected = (
Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376).finished();
167 Matrix H3Expected = (
Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376).finished();
174 Matrix H2Expected = numericalDerivative11<Vector, Pose3>(
176 return factor.evaluateError(pose, body_P_sensor, point, *
K1);
180 Matrix H4Expected = numericalDerivative11<Vector, Cal3_S2>(
182 return factor.evaluateError(pose, body_P_sensor, point,
K);
Provides additional testing facilities for common data structures.
static SharedNoiseModel model(noiseModel::Unit::Create(2))
static int runAllTests(TestResult &result)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Derived from ProjectionFactor, but estimates body-camera transform and calibration in addition to bod...
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
ProjectionFactorPPPC< Pose3, Point3, Cal3_S2 > TestProjectionFactor
static Point2 measurement(323.0, 240.0)
std::shared_ptr< Cal3_S2 > shared_ptr
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Cal3_S2::shared_ptr K1(new Cal3_S2(fov, w, h))
The most common 5DOF 3D->2D calibration.
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
TEST(ProjectionFactorPPPC, nonStandard)
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.