| 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 | |
| 12 | /** |
| 13 | * @file timeLinearize.h |
| 14 | * @brief time linearize |
| 15 | * @author Frank Dellaert |
| 16 | * @date October 10, 2014 |
| 17 | */ |
| 18 | |
| 19 | #pragma once |
| 20 | |
| 21 | #include <gtsam/nonlinear/NonlinearFactorGraph.h> |
| 22 | #include <gtsam/linear/GaussianFactorGraph.h> |
| 23 | |
| 24 | #include <time.h> |
| 25 | #include <iostream> |
| 26 | #include <iomanip> |
| 27 | |
| 28 | static const int n = 1000000; |
| 29 | |
| 30 | void timeSingleThreaded(const std::string& str, |
| 31 | const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { |
| 32 | long timeLog = clock(); |
| 33 | gtsam::GaussianFactor::shared_ptr gf; |
| 34 | for (int i = 0; i < n; i++) |
| 35 | gf = f->linearize(c: 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" |
| 40 | << std::endl; |
| 41 | } |
| 42 | |
| 43 | void timeMultiThreaded(const std::string& str, |
| 44 | const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { |
| 45 | gtsam::NonlinearFactorGraph graph; |
| 46 | for (int i = 0; i < n; i++) |
| 47 | graph.push_back(factor: f); |
| 48 | long timeLog = clock(); |
| 49 | gtsam::GaussianFactorGraph::shared_ptr gfg = graph.linearize(linearizationPoint: values); |
| 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" |
| 54 | << std::endl; |
| 55 | } |
| 56 | |
| 57 |