30 using namespace gtsam;
33 static double fov = 60;
34 static size_t w=640,
h=480;
47 TEST( ProjectionFactor, nonStandard ) {
52 TEST( ProjectionFactor, Constructor) {
58 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K);
62 TEST( ProjectionFactor, ConstructorWithTransform) {
67 Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
Point3(0.25, -0.10, 1.0));
69 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K, body_P_sensor);
73 TEST( ProjectionFactor, Equals ) {
84 TEST( ProjectionFactor, EqualsWithTransform ) {
87 Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
Point3(0.25, -0.10, 1.0));
89 TestProjectionFactor
factor1(measurement,
model,
X(1),
L(1),
K, body_P_sensor);
90 TestProjectionFactor
factor2(measurement,
model,
X(1),
L(1),
K, body_P_sensor);
96 TEST( ProjectionFactor, Error ) {
101 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K);
118 TEST( ProjectionFactor, ErrorWithTransform ) {
123 Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
Point3(0.25, -0.10, 1.0));
124 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K, body_P_sensor);
141 TEST( ProjectionFactor, Jacobian ) {
146 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K);
153 Matrix H1Actual, H2Actual;
157 Matrix H1Expected = (
Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.).finished();
158 Matrix H2Expected = (
Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.).finished();
166 TEST( ProjectionFactor, JacobianWithTransform ) {
171 Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2),
Point3(0.25, -0.10, 1.0));
172 TestProjectionFactor factor(measurement,
model, poseKey, pointKey,
K, body_P_sensor);
179 Matrix H1Actual, H2Actual;
183 Matrix H1Expected = (
Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376).finished();
184 Matrix H2Expected = (
Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376).finished();
Provides additional testing facilities for common data structures.
GenericProjectionFactor< Pose3, Point3 > TestProjectionFactor
static int runAllTests(TestResult &result)
static Cal3_S2::shared_ptr K(new Cal3_S2(fov, w, h))
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
TEST(ProjectionFactor, nonStandard)
const gtsam::Key pointKey
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Basic bearing factor from 2D measurement.
Vector evaluateError(const Pose3 &pose, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
JacobianFactor factor2(keyX, A21, keyY, A22, b2, noiseModel::Isotropic::Sigma(2, sigma2))
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
boost::shared_ptr< Cal3_S2 > shared_ptr
static SharedNoiseModel model(noiseModel::Unit::Create(2))
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))