33 using namespace gtsam;
36 static double fov = 60;
37 static size_t w=640,
h=480;
53 struct traits<TestProjectionFactor> :
public Testable<TestProjectionFactor> {
65 Key transformKey(
T(1));
70 TestProjectionFactor factor(measurement,
model, poseKey, transformKey, pointKey,
K);
76 Key transformKey(
T(1));
80 TestProjectionFactor factor(measurement,
model, poseKey, transformKey, pointKey,
K);
110 Key transformKey(
T(1));
113 TestProjectionFactor factor(measurement,
model, poseKey, transformKey, pointKey,
K);
133 Key transformKey(
T(1));
137 TestProjectionFactor factor(measurement,
model, poseKey,transformKey, pointKey,
K);
157 Key transformKey(
T(1));
160 TestProjectionFactor factor(measurement,
model, poseKey, transformKey, pointKey,
K);
167 Matrix H1Actual, H2Actual, H3Actual;
171 Matrix H1Expected = (
Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.).finished();
172 Matrix H3Expected = (
Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.).finished();
179 Matrix H2Expected = numericalDerivative32<Vector, Pose3, Pose3, Point3>(
192 Key transformKey(
T(1));
196 TestProjectionFactor factor(measurement,
model, poseKey, transformKey, pointKey,
K);
203 Matrix H1Actual, H2Actual, H3Actual;
204 factor.
evaluateError(pose, body_P_sensor, point, H1Actual, H2Actual, H3Actual);
207 Matrix H1Expected = (
Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376).finished();
208 Matrix H3Expected = (
Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376).finished();
215 Matrix H2Expected = numericalDerivative32<Vector, Pose3, Pose3, Point3>(
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))
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...
const gtsam::Key pointKey
static Cal3_S2::shared_ptr K(new Cal3_S2(fov, w, h))
static Point2 measurement(323.0, 240.0)
std::shared_ptr< Cal3_S2 > shared_ptr
ProjectionFactorPPP< Pose3, Point3 > TestProjectionFactor
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(ProjectionFactorPPP, nonStandard)
Derived from ProjectionFactor, but estimates body-camera transform in addition to body pose and 3D la...
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
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.