23 using namespace gtsam;
42 double r =
p.x() *
p.x() +
p.y() *
p.y();
43 double g = v[0] * (1 + v[1] * r + v[2] * r * r);
111 std::stringstream
os;
112 os <<
"f: " << cal.
fx() <<
", k1: " << cal.
k1() <<
", k2: " << cal.
k2()
113 <<
", px: " << cal.
px() <<
", py: " << cal.
py();
bool assert_stdout_equal(const std::string &expected, const V &actual)
Provides additional testing facilities for common data structures.
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
double k1() const
distorsion parameter k1
double k2() const
distorsion parameter k2
Some functions to compute numerical derivatives.
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
static const Point3 pt(1.0, 2.0, 3.0)
void g(const string &key, int i)
Cal3Bundler retract(const Vector &d) const
Update calibration with tangent space delta.
Point2 calibrate(const Point2 &pi, OptionalJacobian< 2, 3 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
static Cal3Bundler K(500, 1e-3, 1e-3, 1000, 2000)
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double px() const
image center in x
Point2 uncalibrate_(const Cal3Bundler &k, const Point2 &pt)
size_t dim() const override
return DOF, dimensionality of tangent space
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
#define GTSAM_CONCEPT_MANIFOLD_INST(T)
#define EXPECT_LONGS_EQUAL(expected, actual)
ofstream os("timeSchurFactors.csv")
Vector3 localCoordinates(const Cal3Bundler &T2) const
Calculate local coordinates to another calibration.
Point2_ uncalibrate(const Expression< CALIBRATION > &K, const Point2_ &xy_hat)
TEST(LPInitSolver, InfiniteLoopSingleVar)
double fx() const
focal length x
static size_t Dim()
return DOF, dimensionality of tangent space
double py() const
image center in y
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Calibration used by Bundler.
#define GTSAM_CONCEPT_TESTABLE_INST(T)
Point2 uncalibrate(const Point2 &p, OptionalJacobian< 2, 3 > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none) const
: convert intrinsic coordinates xy to image coordinates uv Version of uncalibrate with derivatives ...
Point2 calibrate_(const Cal3Bundler &k, const Point2 &pt)