Go to the documentation of this file.
25 using namespace gtsam;
41 ZZ
z =
set.project2(
p);
57 set.project2(
p, Fs,
E);
87 ZZ
z =
set.project2(
p);
105 set.project2(
p, Fs,
E);
128 actualE.resize(4, 2);
static int runAllTests(TestResult &result)
A CameraSet of either CalibratedCamera, PinholePose, or PinholeCamera.
#define EXPECT_LONGS_EQUAL(expected, actual)
#define EXPECT(condition)
static const SmartProjectionParams params
Calibrated camera for which only pose is unknown.
Some functions to compute numerical derivatives.
Base class for all pinhole cameras.
Point3 expectedV(0.29552, 0.0446635, 1)
void set(Container &c, Position position, const Value &value)
Point2 project2(const Point3 &point, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}) const
PinholePose< Cal3_S2 > Camera
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
std::vector< Point2, Eigen::aligned_allocator< Point2 > > Point2Vector
Represents a 3D point on a unit sphere.
static const CalibratedCamera camera(kDefaultPose)
Unit3 pointAtInfinity(0, 0, -1000)
Calibration used by Bundler.
#define LONGS_EQUAL(expected, actual)
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:06:52