29 using namespace gtsam;
36 static const size_t M=100,
N = 10000,
n = M*
N;
40 std::vector<Expression<Pose3> >
x = createUnknowns<Pose3>(
M,
'x');
41 std::vector<Expression<Point3> >
p = createUnknowns<Point3>(
N,
'p');
50 for (
size_t i = 0;
i <
M;
i++)
52 for (
size_t j = 0;
j <
N;
j++)
55 long timeLog = clock();
57 for (
size_t i = 0;
i <
M;
i++) {
58 for (
size_t j = 0;
j <
N;
j++) {
69 long timeLog2 = clock();
70 cout << setprecision(3);
71 double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
72 cout << seconds <<
" seconds to build" << endl;
77 seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
78 cout << seconds <<
" seconds to linearize" << endl;
79 cout << ((double) seconds * 1000000 /
n) <<
" musecs/call" << endl;
Matrix< RealScalar, Dynamic, Dynamic > M
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
Factor Graph consisting of non-linear factors.
noiseModel::Diagonal::shared_ptr model
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
NonlinearFactorGraph graph
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Linear Factor Graph where all factors are Gaussians.
The most common 5DOF 3D->2D calibration.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
void insert(Key j, const Value &val)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
static Point2 project3(const Pose3 &pose, const Point3 &point, const Cal3_S2 &cal)
noiseModel::Base::shared_ptr SharedNoiseModel
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)