| 
									
										
										
										
											2010-10-14 12:54:38 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2010-10-14 12:54:38 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-10-14 11:23:14 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file testGaussianJunctionTree.cpp | 
					
						
							|  |  |  |  * @date Jul 8, 2010 | 
					
						
							|  |  |  |  * @author nikai | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/base/TestableAssertions.h>
 | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <boost/assign/list_of.hpp>
 | 
					
						
							|  |  |  | #include <boost/assign/std/list.hpp> // for operator +=
 | 
					
						
							|  |  |  | #include <boost/assign/std/set.hpp> // for operator +=
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <boost/assign/std/vector.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | using namespace boost::assign; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-08-18 21:18:26 +08:00
										 |  |  | // Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
 | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | #define GTSAM_MAGIC_KEY
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-09-23 10:50:46 +08:00
										 |  |  | #include <gtsam/base/debug.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/cholesky.h>
 | 
					
						
							|  |  |  | #include <gtsam/inference/BayesTree-inl.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/nonlinear/Ordering.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/linear/GaussianJunctionTree.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | #include <gtsam/linear/GaussianSequentialSolver.h>
 | 
					
						
							| 
									
										
										
										
											2011-09-23 10:50:46 +08:00
										 |  |  | #include <gtsam/linear/GaussianMultifrontalSolver.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-20 01:23:19 +08:00
										 |  |  | #include <gtsam/slam/smallExample.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | #include <gtsam/slam/planarSLAM.h>
 | 
					
						
							| 
									
										
										
										
											2011-09-23 10:50:46 +08:00
										 |  |  | #include <gtsam/slam/pose2SLAM.h>
 | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | using namespace example; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* *
 | 
					
						
							|  |  |  |  Bayes tree for smoother with "nested dissection" ordering: | 
					
						
							|  |  |  | 	 C1		 x5 x6 x4 | 
					
						
							|  |  |  | 	 C2		  x3 x2 : x4 | 
					
						
							|  |  |  | 	 C3		    x1 : x2 | 
					
						
							|  |  |  | 	 C4		  x7 : x6 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | */ | 
					
						
							| 
									
										
										
										
											2010-07-14 06:03:18 +08:00
										 |  |  | TEST( GaussianJunctionTree, constructor2 ) | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	// create a graph
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ordering ordering; ordering += "x1","x3","x5","x7","x2","x6","x4"; | 
					
						
							|  |  |  |   GaussianFactorGraph fg = createSmoother(7, ordering).first; | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// create an ordering
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	GaussianJunctionTree actual(fg); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-12 05:14:35 +08:00
										 |  |  | 	vector<Index> frontal1; frontal1 += ordering["x5"], ordering["x6"], ordering["x4"]; | 
					
						
							|  |  |  | 	vector<Index> frontal2; frontal2 += ordering["x3"], ordering["x2"]; | 
					
						
							|  |  |  | 	vector<Index> frontal3; frontal3 += ordering["x1"]; | 
					
						
							|  |  |  | 	vector<Index> frontal4; frontal4 += ordering["x7"]; | 
					
						
							|  |  |  | 	vector<Index> sep1; | 
					
						
							|  |  |  | 	vector<Index> sep2; sep2 += ordering["x4"]; | 
					
						
							|  |  |  | 	vector<Index> sep3; sep3 += ordering["x2"]; | 
					
						
							|  |  |  | 	vector<Index> sep4; sep4 += ordering["x6"]; | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(frontal1, actual.root()->frontal)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(sep1,     actual.root()->separator)); | 
					
						
							| 
									
										
										
										
											2010-07-15 07:48:51 +08:00
										 |  |  | 	LONGS_EQUAL(5,               actual.root()->size()); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	list<GaussianJunctionTree::sharedClique>::const_iterator child0it = actual.root()->children().begin(); | 
					
						
							|  |  |  |   list<GaussianJunctionTree::sharedClique>::const_iterator child1it = child0it; ++child1it; | 
					
						
							|  |  |  |   GaussianJunctionTree::sharedClique child0 = *child0it; | 
					
						
							|  |  |  |   GaussianJunctionTree::sharedClique child1 = *child1it; | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(frontal2, child0->frontal)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(sep2,     child0->separator)); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | 	LONGS_EQUAL(4,               child0->size()); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(frontal3, child0->children().front()->frontal)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(sep3,     child0->children().front()->separator)); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | 	LONGS_EQUAL(2,               child0->children().front()->size()); | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  | 	EXPECT(assert_equal(frontal4, child1->frontal)); | 
					
						
							|  |  |  | 	EXPECT(assert_equal(sep4,     child1->separator)); | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  | 	LONGS_EQUAL(2,               child1->size()); | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-19 04:23:23 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-07-14 06:03:18 +08:00
										 |  |  | TEST( GaussianJunctionTree, optimizeMultiFrontal ) | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | { | 
					
						
							|  |  |  | 	// create a graph
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   GaussianFactorGraph fg; | 
					
						
							|  |  |  |   Ordering ordering; | 
					
						
							|  |  |  |   boost::tie(fg,ordering) = createSmoother(7); | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// optimize the graph
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	GaussianJunctionTree tree(fg); | 
					
						
							| 
									
										
										
										
											2011-03-25 03:27:12 +08:00
										 |  |  | 	VectorValues actual = tree.optimize(&EliminateQR); | 
					
						
							| 
									
										
										
										
											2010-07-19 04:23:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// verify
 | 
					
						
							| 
									
										
										
										
											2010-10-23 02:02:55 +08:00
										 |  |  | 	VectorValues expected(vector<size_t>(7,2)); // expected solution
 | 
					
						
							| 
									
										
										
										
											2010-07-19 04:23:23 +08:00
										 |  |  | 	Vector v = Vector_(2, 0., 0.); | 
					
						
							|  |  |  | 	for (int i=1; i<=7; i++) | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 		expected[ordering[Symbol('x',i)]] = v; | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2010-07-19 04:23:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST( GaussianJunctionTree, optimizeMultiFrontal2) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  | 	// create a graph
 | 
					
						
							| 
									
										
										
										
											2011-11-07 03:08:42 +08:00
										 |  |  | 	example::Graph nlfg = createNonlinearFactorGraph(); | 
					
						
							|  |  |  | 	example::Values noisy = createNoisyValues(); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   Ordering ordering; ordering += "x1","x2","l1"; | 
					
						
							|  |  |  | 	GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering); | 
					
						
							| 
									
										
										
										
											2010-07-19 04:23:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// optimize the graph
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 	GaussianJunctionTree tree(fg); | 
					
						
							| 
									
										
										
										
											2011-03-25 03:27:12 +08:00
										 |  |  | 	VectorValues actual = tree.optimize(&EliminateQR); | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// verify
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | 	VectorValues expected = createCorrectDelta(ordering); // expected solution
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected,actual)); | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(GaussianJunctionTree, slamlike) { | 
					
						
							|  |  |  |   typedef planarSLAM::PoseKey PoseKey; | 
					
						
							|  |  |  |   typedef planarSLAM::PointKey PointKey; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   planarSLAM::Values init; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   planarSLAM::Graph newfactors; | 
					
						
							|  |  |  |   planarSLAM::Graph fullgraph; | 
					
						
							|  |  |  |   SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0)); | 
					
						
							|  |  |  |   SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   size_t i = 0; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   newfactors = planarSLAM::Graph(); | 
					
						
							|  |  |  |   newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise); | 
					
						
							|  |  |  |   init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01)); | 
					
						
							|  |  |  |   fullgraph.push_back(newfactors); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   for( ; i<5; ++i) { | 
					
						
							|  |  |  |     newfactors = planarSLAM::Graph(); | 
					
						
							|  |  |  |     newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); | 
					
						
							|  |  |  |     init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); | 
					
						
							|  |  |  |     fullgraph.push_back(newfactors); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   newfactors = planarSLAM::Graph(); | 
					
						
							|  |  |  |   newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); | 
					
						
							|  |  |  |   newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise); | 
					
						
							|  |  |  |   newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise); | 
					
						
							|  |  |  |   init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01)); | 
					
						
							|  |  |  |   init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0))); | 
					
						
							|  |  |  |   init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0))); | 
					
						
							|  |  |  |   fullgraph.push_back(newfactors); | 
					
						
							|  |  |  |   ++ i; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   for( ; i<5; ++i) { | 
					
						
							|  |  |  |     newfactors = planarSLAM::Graph(); | 
					
						
							|  |  |  |     newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); | 
					
						
							|  |  |  |     init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01)); | 
					
						
							|  |  |  |     fullgraph.push_back(newfactors); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   newfactors = planarSLAM::Graph(); | 
					
						
							|  |  |  |   newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise); | 
					
						
							|  |  |  |   newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise); | 
					
						
							|  |  |  |   newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise); | 
					
						
							|  |  |  |   init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01)); | 
					
						
							|  |  |  |   fullgraph.push_back(newfactors); | 
					
						
							|  |  |  |   ++ i; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Compare solutions
 | 
					
						
							| 
									
										
										
										
											2010-10-15 23:53:36 +08:00
										 |  |  |   Ordering ordering = *fullgraph.orderingCOLAMD(init); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  |   GaussianFactorGraph linearized = *fullgraph.linearize(init, ordering); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   GaussianJunctionTree gjt(linearized); | 
					
						
							| 
									
										
										
										
											2011-03-25 03:27:12 +08:00
										 |  |  |   VectorValues deltaactual = gjt.optimize(&EliminateQR); | 
					
						
							| 
									
										
										
										
											2011-11-05 05:44:34 +08:00
										 |  |  |   planarSLAM::Values actual = init.retract(deltaactual, ordering); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 06:59:54 +08:00
										 |  |  |   GaussianBayesNet gbn = *GaussianSequentialSolver(linearized).eliminate(); | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  |   VectorValues delta = optimize(gbn); | 
					
						
							| 
									
										
										
										
											2011-11-05 05:44:34 +08:00
										 |  |  |   planarSLAM::Values expected = init.retract(delta, ordering); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-06-14 00:55:31 +08:00
										 |  |  |   EXPECT(assert_equal(expected, actual)); | 
					
						
							| 
									
										
										
										
											2011-09-23 10:50:46 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST(GaussianJunctionTree, simpleMarginal) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   typedef BayesTree<GaussianConditional> GaussianBayesTree; | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-09-23 10:50:46 +08:00
										 |  |  |   // Create a simple graph
 | 
					
						
							|  |  |  |   pose2SLAM::Graph fg; | 
					
						
							|  |  |  |   fg.addPrior(pose2SLAM::Key(0), Pose2(), sharedSigma(3, 10.0)); | 
					
						
							|  |  |  |   fg.addConstraint(0, 1, Pose2(1.0, 0.0, 0.0), sharedSigmas(Vector_(3, 10.0, 1.0, 1.0))); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   pose2SLAM::Values init; | 
					
						
							|  |  |  |   init.insert(0, Pose2()); | 
					
						
							|  |  |  |   init.insert(1, Pose2(1.0, 0.0, 0.0)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Ordering ordering; | 
					
						
							|  |  |  |   ordering += "x1", "x0"; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   GaussianFactorGraph gfg = *fg.linearize(init, ordering); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Compute marginals with both sequential and multifrontal
 | 
					
						
							|  |  |  |   Matrix expected = GaussianSequentialSolver(gfg).marginalCovariance(1); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix actual1 = GaussianMultifrontalSolver(gfg).marginalCovariance(1); | 
					
						
							|  |  |  |    | 
					
						
							|  |  |  |   // Compute marginal directly from marginal factor
 | 
					
						
							|  |  |  |   GaussianFactor::shared_ptr marginalFactor = GaussianMultifrontalSolver(gfg).marginalFactor(1); | 
					
						
							|  |  |  |   JacobianFactor::shared_ptr marginalJacobian = boost::dynamic_pointer_cast<JacobianFactor>(marginalFactor); | 
					
						
							|  |  |  |   Matrix actual2 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Compute marginal directly from BayesTree
 | 
					
						
							|  |  |  |   GaussianBayesTree gbt; | 
					
						
							|  |  |  |   gbt.insert(GaussianJunctionTree(gfg).eliminate(EliminateLDL)); | 
					
						
							|  |  |  |   marginalFactor = gbt.marginalFactor(1, EliminateLDL); | 
					
						
							|  |  |  |   marginalJacobian = boost::dynamic_pointer_cast<JacobianFactor>(marginalFactor); | 
					
						
							|  |  |  |   Matrix actual3 = inverse(marginalJacobian->getA(marginalJacobian->begin()).transpose() * marginalJacobian->getA(marginalJacobian->begin())); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, actual1)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, actual2)); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expected, actual3)); | 
					
						
							| 
									
										
										
										
											2010-10-09 06:04:47 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-07-12 15:16:31 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr);} | 
					
						
							|  |  |  | /* ************************************************************************* */ |