| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | 
					
						
							|  |  |  |  * 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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /**
 | 
					
						
							| 
									
										
										
										
											2010-11-04 06:35:02 +08:00
										 |  |  |  * @file    timeSequentialOnDataset.cpp | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |  * @author  Richard Roberts | 
					
						
							| 
									
										
										
										
											2011-10-23 03:57:36 +08:00
										 |  |  |  * @date    Oct 7, 2010 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/base/timing.h>
 | 
					
						
							|  |  |  | #include <gtsam/slam/dataset.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2010-11-04 06:35:02 +08:00
										 |  |  | #include <gtsam/linear/GaussianSequentialSolver.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace boost; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | int main(int argc, char *argv[]) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   string datasetname; | 
					
						
							| 
									
										
										
										
											2011-05-20 21:52:08 +08:00
										 |  |  |   bool soft_prior = true; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   if(argc > 1) | 
					
						
							|  |  |  |     datasetname = argv[1]; | 
					
						
							|  |  |  |   else | 
					
						
							|  |  |  |     datasetname = "intel"; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 01:14:24 +08:00
										 |  |  |   // check if there should be a constraint
 | 
					
						
							| 
									
										
										
										
											2011-05-20 21:52:08 +08:00
										 |  |  |   if (argc == 3 && string(argv[2]).compare("-c") == 0) | 
					
						
							|  |  |  |   	soft_prior = false; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 01:14:24 +08:00
										 |  |  |   // find the number of trials - default is 10
 | 
					
						
							|  |  |  |   size_t nrTrials = 10; | 
					
						
							|  |  |  |   if (argc == 3 && string(argv[2]).compare("-c") != 0) | 
					
						
							|  |  |  |   	nrTrials = strtoul(argv[2], NULL, 10); | 
					
						
							|  |  |  |   else if (argc == 4) | 
					
						
							|  |  |  |   	nrTrials = strtoul(argv[3], NULL, 10); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-05 02:46:05 +08:00
										 |  |  |   pair<boost::shared_ptr<pose2SLAM::Graph>, boost::shared_ptr<Values> > data = load2D(dataset(datasetname)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-11-20 00:30:06 +08:00
										 |  |  |   // Add a prior on the first pose
 | 
					
						
							| 
									
										
										
										
											2011-05-20 21:52:08 +08:00
										 |  |  |   if (soft_prior) | 
					
						
							|  |  |  |   	data.first->addPrior(0, Pose2(), sharedSigma(Pose2::Dim(), 0.0005)); | 
					
						
							|  |  |  |   else | 
					
						
							| 
									
										
										
										
											2012-01-28 10:31:44 +08:00
										 |  |  |   	data.first->addPoseConstraint(0, Pose2()); | 
					
						
							| 
									
										
										
										
											2010-11-20 00:30:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-01-21 06:22:00 +08:00
										 |  |  |   tic_(1, "order"); | 
					
						
							| 
									
										
										
										
											2010-10-15 23:53:36 +08:00
										 |  |  |   Ordering::shared_ptr ordering(data.first->orderingCOLAMD(*data.second)); | 
					
						
							| 
									
										
										
										
											2011-01-21 06:22:00 +08:00
										 |  |  |   toc_(1, "order"); | 
					
						
							| 
									
										
										
										
											2010-10-29 23:00:57 +08:00
										 |  |  |   tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-01-21 06:22:00 +08:00
										 |  |  |   tic_(2, "linearize"); | 
					
						
							|  |  |  |   GaussianFactorGraph::shared_ptr gfg(data.first->linearize(*data.second, *ordering)->dynamicCastFactors<GaussianFactorGraph>()); | 
					
						
							|  |  |  |   toc_(2, "linearize"); | 
					
						
							| 
									
										
										
										
											2010-10-29 23:00:57 +08:00
										 |  |  |   tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 01:14:24 +08:00
										 |  |  |   for(size_t trial = 0; trial < nrTrials; ++trial) { | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-01-21 06:22:00 +08:00
										 |  |  |     tic_(3, "solve"); | 
					
						
							|  |  |  |     tic(1, "construct solver"); | 
					
						
							|  |  |  |     GaussianSequentialSolver solver(*gfg); | 
					
						
							|  |  |  |     toc(1, "construct solver"); | 
					
						
							|  |  |  |     tic(2, "optimize"); | 
					
						
							|  |  |  |     VectorValues soln(*solver.optimize()); | 
					
						
							|  |  |  |     toc(2, "optimize"); | 
					
						
							|  |  |  |     toc_(3, "solve"); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  |     tictoc_print_(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } |