29 using namespace gtsam;
31 #define time timeMultiThreaded 54 NonlinearFactor::shared_ptr
f1,
f2,
f3;
57 f1 = std::make_shared<GeneralSFMFactor<Camera, Point3> >(
z,
model, 1, 2);
58 time(
"GeneralSFMFactor<Camera> : ", f1, values);
62 f3 = std::make_shared<ExpressionFactor<Point2> >(
model,
z, expression2);
63 time(
"Point2_(camera, &Camera::project, point): ", f3, values);
67 values.
insert(1,Vector9(Vector9::Zero()));
71 f2 = std::make_shared<ExpressionFactor<Vector2> >(
model,
z, expression);
72 time(
"Point2_(AdaptedSnavely(), camera, point): ", f2, values);
Expression< Point3 > Point3_
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
Adaptor for Ceres style auto-differentiated functions.
noiseModel::Diagonal::shared_ptr model
Expression< Point2 > Point2_
double f2(const Vector2 &x)
Base class for all pinhole cameras.
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
double f3(double x1, double x2)
void insert(Key j, const Value &val)
PinholePose< Cal3_S2 > Camera
static const CalibratedCamera camera(kDefaultPose)
a general SFM factor with an unknown calibration
Calibration used by Bundler.
noiseModel::Base::shared_ptr SharedNoiseModel