32 using namespace gtsam;
35 static double fov = 60;
36 static size_t w = 640,
h = 480;
109 Pose3 body_P_sensor2(
110 Rot3::RzRyRx(0.0, 0.0, 0.0),
111 Point3(0.25, -0.10, 1.0));
195 Pose3 body_P_sensor3(Rot3::RzRyRx(-0.1, -0.1, 0.0),
Point3(0, 0.2, 0.1));
230 Matrix H1Actual, H2Actual, H3Actual;
231 factor.
evaluateError(pose1, pose2, point, H1Actual, H2Actual, H3Actual);
255 Pose3 body_P_sensor3(Rot3::RzRyRx(-0.1, -0.1, 0.0),
Point3(0, 0.2, 0.1));
265 Matrix H1Actual, H2Actual, H3Actual;
266 factor.
evaluateError(pose1, pose2, point, H1Actual, H2Actual, H3Actual);
293 #ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION 296 bool throwCheirality =
true;
297 bool verboseCheirality =
true;
300 throwCheirality, verboseCheirality);
306 bool throwCheirality =
false;
307 bool verboseCheirality =
false;
310 throwCheirality, verboseCheirality);
313 Matrix H1Actual, H2Actual, H3Actual;
315 H2Actual, H3Actual));
318 Vector expectedError = Vector2::Constant(
330 Point2 measured = camera.project(point);
337 Matrix H1Actual, H2Actual, H3Actual;
338 factor.
evaluateError(pose1, pose2, point, H1Actual, H2Actual, H3Actual);
341 Matrix H1Expected = numericalDerivative31<Vector, Pose3, Pose3, Point3>(
342 std::function<Vector(const Pose3&, const Pose3&, const Point3&)>(
343 std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor,
344 std::placeholders::_1, std::placeholders::_2,
345 std::placeholders::_3, {}, {},
349 Matrix H2Expected = numericalDerivative32<Vector, Pose3, Pose3, Point3>(
350 std::function<Vector(const Pose3&, const Pose3&, const Point3&)>(
351 std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor,
352 std::placeholders::_1, std::placeholders::_2,
353 std::placeholders::_3, {}, {},
357 Matrix H3Expected = numericalDerivative33<Vector, Pose3, Pose3, Point3>(
358 std::function<Vector(const Pose3&, const Pose3&, const Point3&)>(
359 std::bind(&ProjectionFactorRollingShutter::evaluateError, &factor,
360 std::placeholders::_1, std::placeholders::_2,
361 std::placeholders::_3, {}, {},
Provides additional testing facilities for common data structures.
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 double interp_params
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Some functions to compute numerical derivatives.
#define CHECK_EXCEPTION(condition, exception_name)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Basic projection factor for rolling shutter cameras.
static Cal3_S2::shared_ptr K(new Cal3_S2(fov, w, h))
static Key pointKey(L(1))
static Point2 measurement(323.0, 240.0)
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
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.)
The most common 5DOF 3D->2D calibration.
static SharedNoiseModel model(noiseModel::Unit::Create(2))
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
static Key poseKey1(X(1))
TEST(ProjectionFactorRollingShutter, Constructor)
Vector evaluateError(const Pose3 &pose_a, const Pose3 &pose_b, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Evaluate error h(x)-z and optionally derivatives.
static Key poseKey2(X(2))
static const CalibratedCamera camera(kDefaultPose)
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.