| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2019-02-11 22:39:48 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  * @file    timeLinearize.h | 
					
						
							|  |  |  |  * @brief   time linearize | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  * @date    October 10, 2014 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #pragma once
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/NonlinearFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <time.h>
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  | #include <iomanip>
 | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | static const int n = 1000000; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  | void timeSingleThreaded(const std::string& str, | 
					
						
							|  |  |  |     const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  |   long timeLog = clock(); | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  |   gtsam::GaussianFactor::shared_ptr gf; | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  |   for (int i = 0; i < n; i++) | 
					
						
							|  |  |  |     gf = f->linearize(values); | 
					
						
							|  |  |  |   long timeLog2 = clock(); | 
					
						
							|  |  |  |   double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC; | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  |   std::cout << std::setprecision(3); | 
					
						
							|  |  |  |   std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call" | 
					
						
							|  |  |  |       << std::endl; | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  | void timeMultiThreaded(const std::string& str, | 
					
						
							|  |  |  |     const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { | 
					
						
							|  |  |  |   gtsam::NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  |   for (int i = 0; i < n; i++) | 
					
						
							|  |  |  |     graph.push_back(f); | 
					
						
							|  |  |  |   long timeLog = clock(); | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  |   gtsam::GaussianFactorGraph::shared_ptr gfg = graph.linearize(values); | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  |   long timeLog2 = clock(); | 
					
						
							|  |  |  |   double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC; | 
					
						
							| 
									
										
										
										
											2014-10-15 17:01:27 +08:00
										 |  |  |   std::cout << std::setprecision(3); | 
					
						
							|  |  |  |   std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call" | 
					
						
							|  |  |  |       << std::endl; | 
					
						
							| 
									
										
										
										
											2014-10-10 23:17:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 |