23 #include <boost/bind.hpp> 26 using namespace gtsam;
34 set.push_back(camera);
35 set.push_back(camera);
42 ZZ
z =
set.project2(p);
58 set.project2(p, Fs, E);
78 set.push_back(camera);
79 set.push_back(camera);
83 set2.push_back(camera);
88 ZZ
z =
set.project2(p);
97 camera.project2(p, F1, E1);
106 set.project2(p, Fs, E);
115 measured.push_back(
Point2(1, 2));
116 measured.push_back(
Point2(3, 4));
120 expectedV << -1, -2, -3, -4;
121 Vector actualV =
set.reprojectionError(p, measured);
128 camera.project2(pointAtInfinity, F1, E1);
129 actualE.resize(4, 2);
134 camera.backprojectPointAtInfinity(
Point2(0,0))));
138 actualV =
set.reprojectionError(pointAtInfinity, measured, Fs, E);
static int runAllTests(TestResult &result)
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none) const
Some functions to compute numerical derivatives.
Unit3 pointAtInfinity(0, 0,-1000)
Represents a 3D point on a unit sphere.
Base class for all pinhole cameras.
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
#define EXPECT(condition)
A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera.
static SmartStereoProjectionParams params
Calibrated camera for which only pose is unknown.
#define LONGS_EQUAL(expected, actual)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define EXPECT_LONGS_EQUAL(expected, actual)
PinholePose< Cal3_S2 > Camera
static const CalibratedCamera camera(kDefaultPose)
Calibration used by Bundler.