28 static const int n = 1000000;
32 long timeLog = clock();
34 for (
int i = 0;
i <
n;
i++)
35 gf = f->linearize(values);
36 long timeLog2 = clock();
37 double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
38 std::cout << std::setprecision(3);
39 std::cout << str << ((double) seconds * 1000000 / n) <<
" musecs/call" 46 for (
int i = 0;
i <
n;
i++)
48 long timeLog = clock();
50 long timeLog2 = clock();
51 double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
52 std::cout << std::setprecision(3);
53 std::cout << str << ((double) seconds * 1000000 / n) <<
" musecs/call"
Factor Graph consisting of non-linear factors.
void timeSingleThreaded(const std::string &str, const gtsam::NonlinearFactor::shared_ptr &f, const gtsam::Values &values)
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Linear Factor Graph where all factors are Gaussians.
std::shared_ptr< This > shared_ptr
shared_ptr to this class
std::shared_ptr< This > shared_ptr
shared_ptr to this class
void timeMultiThreaded(const std::string &str, const gtsam::NonlinearFactor::shared_ptr &f, const gtsam::Values &values)
std::shared_ptr< This > shared_ptr