timeSFMExpressions.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/slam/expressions.h>
23 
24 #include <time.h>
25 #include <iostream>
26 #include <iomanip> // std::setprecision
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 //#define TERNARY
32 
33 int main() {
34 
35  // number of cameras, and points
36  static const size_t M=100, N = 10000, n = M*N;
37 
38  // Create leaves
39  Cal3_S2_ K('K', 0);
40  std::vector<Expression<Pose3> > x = createUnknowns<Pose3>(M, 'x');
41  std::vector<Expression<Point3> > p = createUnknowns<Point3>(N, 'p');
42 
43  // Some parameters needed
44  Point2 z(-17, 30);
45  SharedNoiseModel model = noiseModel::Unit::Create(2);
46 
47  // Create values
48  Values values;
49  values.insert(Symbol('K', 0), Cal3_S2());
50  for (size_t i = 0; i < M; i++)
51  values.insert(Symbol('x', i), Pose3());
52  for (size_t j = 0; j < N; j++)
53  values.insert(Symbol('p', j), Point3(0, 0, 1));
54 
55  long timeLog = clock();
57  for (size_t i = 0; i < M; i++) {
58  for (size_t j = 0; j < N; j++) {
61 #ifdef TERNARY
62  (model, z, project3(x[i], p[j], K));
63 #else
64  (model, z, uncalibrate(K, project(transformTo(x[i], p[j]))));
65 #endif
66  graph.push_back(f);
67  }
68  }
69  long timeLog2 = clock();
70  cout << setprecision(3);
71  double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
72  cout << seconds << " seconds to build" << endl;
73 
74  timeLog = clock();
75  GaussianFactorGraph::shared_ptr gfg = graph.linearize(values);
76  timeLog2 = clock();
77  seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
78  cout << seconds << " seconds to linearize" << endl;
79  cout << ((double) seconds * 1000000 / n) << " musecs/call" << endl;
80 
81  return 0;
82 }
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, boost::shared_ptr< T > > make_shared(Args &&...args)
Definition: make_shared.h:57
int main()
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:38
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
void insert(Key j, const Value &val)
Definition: Values.cpp:140
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Vector2 Point2
Definition: Point2.h:27
int n
leaf::MyValues values
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Definition: Half.h:150
#define N
Definition: gksort.c:12
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
NonlinearFactorGraph graph
boost::shared_ptr< This > shared_ptr
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Linear Factor Graph where all factors are Gaussians.
traits
Definition: chartTesting.h:28
float * p
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Vector3 Point3
Definition: Point3.h:35
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
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)
std::ptrdiff_t j
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:00