| 
									
										
										
										
											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-08-27 23:31:20 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * @brief Unit tests for serialization of library classes | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  * @author Alex Cunningham | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Serialization testing code.
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | #include <sstream>
 | 
					
						
							|  |  |  | #include <string>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // includes for standard serialization types
 | 
					
						
							| 
									
										
										
										
											2011-03-04 22:56:18 +08:00
										 |  |  | #include <boost/serialization/export.hpp>
 | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | #include <boost/serialization/optional.hpp>
 | 
					
						
							|  |  |  | #include <boost/serialization/shared_ptr.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | #include <boost/serialization/vector.hpp>
 | 
					
						
							|  |  |  | #include <boost/serialization/map.hpp>
 | 
					
						
							|  |  |  | #include <boost/serialization/list.hpp>
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | #include <boost/archive/text_oarchive.hpp>
 | 
					
						
							|  |  |  | #include <boost/archive/text_iarchive.hpp>
 | 
					
						
							|  |  |  | #include <boost/archive/xml_iarchive.hpp>
 | 
					
						
							|  |  |  | #include <boost/archive/xml_oarchive.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // whether to print the serialized text to stdout
 | 
					
						
							|  |  |  | const bool verbose = false; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Templated round-trip serialization
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							|  |  |  | void roundtrip(const T& input, T& output) { | 
					
						
							|  |  |  | 	// Serialize
 | 
					
						
							|  |  |  | 	std::ostringstream out_archive_stream; | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | 	{ | 
					
						
							|  |  |  | 		boost::archive::text_oarchive out_archive(out_archive_stream); | 
					
						
							|  |  |  | 		out_archive << input; | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// Convert to string
 | 
					
						
							|  |  |  | 	std::string serialized = out_archive_stream.str(); | 
					
						
							|  |  |  | 	if (verbose) std::cout << serialized << std::endl << std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// De-serialize
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | 	{ | 
					
						
							|  |  |  | 		std::istringstream in_archive_stream(serialized); | 
					
						
							|  |  |  | 		boost::archive::text_iarchive in_archive(in_archive_stream); | 
					
						
							|  |  |  | 		in_archive >> output; | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // This version requires equality operator
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | bool equality(const T& input = T()) { | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtrip<T>(input,output); | 
					
						
							|  |  |  | 	return input==output; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // This version requires equals
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | bool equalsObj(const T& input = T()) { | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtrip<T>(input,output); | 
					
						
							|  |  |  | 	return input.equals(output); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // De-referenced version for pointers
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							|  |  |  | bool equalsDereferenced(const T& input) { | 
					
						
							|  |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtrip<T>(input,output); | 
					
						
							|  |  |  | 	return input->equals(*output); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Templated round-trip serialization using XML
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							|  |  |  | void roundtripXML(const T& input, T& output) { | 
					
						
							|  |  |  | 	// Serialize
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | 	std::string serialized; | 
					
						
							|  |  |  | 	{ | 
					
						
							|  |  |  | 		std::ostringstream out_archive_stream; | 
					
						
							|  |  |  | 		boost::archive::xml_oarchive out_archive(out_archive_stream); | 
					
						
							|  |  |  | 		out_archive << boost::serialization::make_nvp("data", input); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 		// Convert to string
 | 
					
						
							|  |  |  | 		serialized = out_archive_stream.str(); | 
					
						
							|  |  |  | 	} | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 	if (verbose) std::cout << serialized << std::endl << std::endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	// De-serialize
 | 
					
						
							|  |  |  | 	std::istringstream in_archive_stream(serialized); | 
					
						
							|  |  |  | 	boost::archive::xml_iarchive in_archive(in_archive_stream); | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | 	in_archive >> boost::serialization::make_nvp("data", output); | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // This version requires equality operator
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | bool equalityXML(const T& input = T()) { | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtripXML<T>(input,output); | 
					
						
							|  |  |  | 	return input==output; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // This version requires equals
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | bool equalsXML(const T& input = T()) { | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtripXML<T>(input,output); | 
					
						
							|  |  |  | 	return input.equals(output); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | // This version is for pointers
 | 
					
						
							|  |  |  | template<class T> | 
					
						
							|  |  |  | bool equalsDereferencedXML(const T& input = T()) { | 
					
						
							|  |  |  | 	T output; | 
					
						
							|  |  |  | 	roundtripXML<T>(input,output); | 
					
						
							|  |  |  | 	return input->equals(*output); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Actual Tests
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Rot2.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Point3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Pose3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Rot3.h>
 | 
					
						
							|  |  |  | #include <gtsam/geometry/Cal3_S2.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //#include <gtsam/linear/VectorValues.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | //#include <gtsam/linear/GaussianConditional.h>
 | 
					
						
							|  |  |  | //#include <gtsam/inference/SymbolicConditional.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | #include <gtsam/slam/planarSLAM.h>
 | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | #include <gtsam/slam/BearingFactor.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-26 04:10:33 +08:00
										 |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | using namespace planarSLAM; | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | TEST (Serialization, text_geometry) { | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Point2>(Point2(1.0, 2.0))); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3))); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Rot2>(Rot2::fromDegrees(30.0))); | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Point3 pt3(1.0, 2.0, 3.0); | 
					
						
							|  |  |  | 	Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Point3>(pt3)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Rot3>(rt3)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<gtsam::Pose3>(Pose3(rt3, pt3))); | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, xml_geometry) { | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Point2>(Point2(1.0, 2.0))); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Pose2>(Pose2(1.0, 2.0, 0.3))); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Rot2>(Rot2::fromDegrees(30.0))); | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Point3 pt3(1.0, 2.0, 3.0); | 
					
						
							|  |  |  | 	Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Point3>(pt3)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Rot3>(rt3)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<gtsam::Pose3>(Pose3(rt3, pt3))); | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, text_linear) { | 
					
						
							|  |  |  | 	// NOT WORKING:
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	EXPECT(equalsObj<VectorValues>());
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | //	EXPECT(equalsObj<GaussianConditional>());
 | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, xml_linear) { | 
					
						
							|  |  |  | 	// NOT WORKING:
 | 
					
						
							| 
									
										
										
										
											2010-10-09 11:09:58 +08:00
										 |  |  | //	EXPECT(equalsXML<VectorValues>());
 | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | //	EXPECT(equalsXML<GaussianConditional>());
 | 
					
						
							|  |  |  | } | 
					
						
							| 
									
										
										
										
											2011-03-09 02:13:49 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Export Noisemodels
 | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic"); | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-03-09 03:19:21 +08:00
										 |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::SharedGaussian, "gtsam_SharedGaussian"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | // example noise models
 | 
					
						
							|  |  |  | noiseModel::Diagonal::shared_ptr diag3 = noiseModel::Diagonal::Sigmas(Vector_(3, 0.1, 0.2, 0.3)); | 
					
						
							|  |  |  | noiseModel::Gaussian::shared_ptr gaussian3 = noiseModel::Gaussian::SqrtInformation(2.0 * eye(3,3)); | 
					
						
							|  |  |  | noiseModel::Isotropic::shared_ptr iso3 = noiseModel::Isotropic::Sigma(3, 0.2); | 
					
						
							|  |  |  | noiseModel::Constrained::shared_ptr constrained3 = noiseModel::Constrained::MixedSigmas(Vector_(3, 0.0, 0.0, 0.1)); | 
					
						
							|  |  |  | noiseModel::Unit::shared_ptr unit3 = noiseModel::Unit::Create(3); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, noiseModels) { | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 	// tests using pointers to the derived class
 | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 	EXPECT(   equalsDereferenced<noiseModel::Diagonal::shared_ptr>(diag3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<noiseModel::Diagonal::shared_ptr>(diag3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(   equalsDereferenced<noiseModel::Gaussian::shared_ptr>(gaussian3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<noiseModel::Gaussian::shared_ptr>(gaussian3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(   equalsDereferenced<noiseModel::Isotropic::shared_ptr>(iso3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<noiseModel::Isotropic::shared_ptr>(iso3)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 	EXPECT(   equalsDereferenced<noiseModel::Constrained::shared_ptr>(constrained3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<noiseModel::Constrained::shared_ptr>(constrained3)); | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(   equalsDereferenced<noiseModel::Unit::shared_ptr>(unit3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<noiseModel::Unit::shared_ptr>(unit3)); | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, SharedGaussian_noiseModels) { | 
					
						
							| 
									
										
										
										
											2011-03-09 02:13:49 +08:00
										 |  |  | 	SharedGaussian diag3_sg = diag3; | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(diag3_sg)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(diag3_sg)); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(diag3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(diag3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(iso3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(iso3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(gaussian3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(gaussian3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(unit3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(unit3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedGaussian>(constrained3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedGaussian>(constrained3)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | TEST (Serialization, SharedDiagonal_noiseModels) { | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedDiagonal>(diag3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedDiagonal>(diag3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedDiagonal>(iso3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedDiagonal>(iso3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedDiagonal>(unit3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedDiagonal>(unit3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	EXPECT(equalsDereferenced<SharedDiagonal>(constrained3)); | 
					
						
							|  |  |  | 	EXPECT(equalsDereferencedXML<SharedDiagonal>(constrained3)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2011-03-04 22:56:18 +08:00
										 |  |  | /* Create GUIDs for factors */ | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::Prior,       "gtsam::planarSLAM::Prior"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::Bearing,     "gtsam::planarSLAM::Bearing"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::Range,       "gtsam::planarSLAM::Range"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::BearingRange,"gtsam::planarSLAM::BearingRange"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::Odometry,    "gtsam::planarSLAM::Odometry"); | 
					
						
							|  |  |  | BOOST_CLASS_EXPORT_GUID(gtsam::planarSLAM::Constraint,  "gtsam::planarSLAM::Constraint"); | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | TEST (Serialization, planar_system) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	Values values; | 
					
						
							|  |  |  | 	values.insert(PointKey(3), Point2(1.0, 2.0)); | 
					
						
							|  |  |  | 	values.insert(PoseKey(4), Pose2(1.0, 2.0, 0.3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 	SharedGaussian model1 = noiseModel::Isotropic::Sigma(1, 0.3); | 
					
						
							|  |  |  | 	SharedGaussian model2 = noiseModel::Isotropic::Sigma(2, 0.3); | 
					
						
							|  |  |  | 	SharedGaussian model3 = noiseModel::Isotropic::Sigma(3, 0.3); | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Prior prior(PoseKey(3), Pose2(0.1,-0.3, 0.2), model1); | 
					
						
							|  |  |  | 	Bearing bearing(PoseKey(3), PointKey(5), Rot2::fromDegrees(0.5), model1); | 
					
						
							|  |  |  | 	Range range(PoseKey(2), PointKey(9), 7.0, model1); | 
					
						
							|  |  |  | 	BearingRange bearingRange(PoseKey(2), PointKey(3), Rot2::fromDegrees(0.6), 2.0, model2); | 
					
						
							|  |  |  | 	Odometry odometry(PoseKey(2), PoseKey(3), Pose2(1.0, 2.0, 0.3), model3); | 
					
						
							|  |  |  | 	Constraint constraint(PoseKey(9), Pose2(2.0,-1.0, 0.2)); | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	Graph graph; | 
					
						
							|  |  |  | 	graph.add(prior); | 
					
						
							|  |  |  | 	graph.add(bearing); | 
					
						
							|  |  |  | 	graph.add(range); | 
					
						
							|  |  |  | 	graph.add(bearingRange); | 
					
						
							|  |  |  | 	graph.add(odometry); | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 	graph.add(constraint); | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// text
 | 
					
						
							|  |  |  | 	EXPECT(equalsObj<PoseKey>(PoseKey(2))); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<PointKey>(PointKey(3))); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<Values>(values)); | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 	EXPECT(equalsObj<Prior>(prior)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<Bearing>(bearing)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<BearingRange>(bearingRange)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<Range>(range)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<Odometry>(odometry)); | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 	EXPECT(equalsObj<Constraint>(constraint)); | 
					
						
							|  |  |  | 	EXPECT(equalsObj<Graph>(graph)); | 
					
						
							| 
									
										
										
										
											2011-02-23 13:19:07 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | 	// xml
 | 
					
						
							|  |  |  | 	EXPECT(equalsXML<PoseKey>(PoseKey(2))); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<PointKey>(PointKey(3))); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<Values>(values)); | 
					
						
							| 
									
										
										
										
											2011-02-24 04:31:19 +08:00
										 |  |  | 	EXPECT(equalsXML<Prior>(prior)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<Bearing>(bearing)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<BearingRange>(bearingRange)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<Range>(range)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<Odometry>(odometry)); | 
					
						
							| 
									
										
										
										
											2011-03-04 01:16:13 +08:00
										 |  |  | 	EXPECT(equalsXML<Constraint>(constraint)); | 
					
						
							|  |  |  | 	EXPECT(equalsXML<Graph>(graph)); | 
					
						
							| 
									
										
										
										
											2010-08-31 03:16:26 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2010-08-27 23:31:20 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  | 	TestResult tr; | 
					
						
							|  |  |  | 	return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ |